Skip to content

Commit

Permalink
Add new asignment/copy/move ctors to result
Browse files Browse the repository at this point in the history
  • Loading branch information
mcm001 committed Aug 19, 2024
1 parent 76b8ec5 commit 55dad98
Show file tree
Hide file tree
Showing 14 changed files with 124 additions and 77 deletions.
2 changes: 1 addition & 1 deletion photon-lib/py/photonlibpy/photonCamera.py
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ def getLatestResult(self) -> PhotonPipelineResult:
pkt = Packet(byteList)
retVal = PhotonPipelineResult.photonStruct.unpack(pkt)
# We don't trust NT4 time, hack around
retVal.ntRecieveTimestampMicros = now
retVal.ntReceiveTimestampMicros = now
return retVal

def getDriverMode(self) -> bool:
Expand Down
10 changes: 5 additions & 5 deletions photon-lib/py/photonlibpy/targeting/photonPipelineResult.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ class PhotonPipelineMetadata:
@dataclass
class PhotonPipelineResult:
# Since we don't trust NT time sync, keep track of when we got this packet into robot code
ntRecieveTimestampMicros: int = -1
ntReceiveTimestampMicros: int = -1

targets: list[PhotonTrackedTarget] = field(default_factory=list)
metadata: PhotonPipelineMetadata = field(default_factory=PhotonPipelineMetadata)
Expand All @@ -34,13 +34,13 @@ def getLatencyMillis(self) -> float:

def getTimestampSeconds(self) -> float:
"""
Returns the estimated time the frame was taken, in the recieved system's time base. This is
calculated as (NT recieve time (robot base) - (publish timestamp, coproc timebase - capture
Returns the estimated time the frame was taken, in the Received system's time base. This is
calculated as (NT Receive time (robot base) - (publish timestamp, coproc timebase - capture
timestamp, coproc timebase))
"""
# TODO - we don't trust NT4 to correctly latency-compensate ntRecieveTimestampMicros
# TODO - we don't trust NT4 to correctly latency-compensate ntReceiveTimestampMicros
return (
self.ntRecieveTimestampMicros
self.ntReceiveTimestampMicros
- (
self.metadata.publishTimestampMicros
- self.metadata.captureTimestampMicros
Expand Down
6 changes: 3 additions & 3 deletions photon-lib/src/main/java/org/photonvision/PhotonCamera.java
Original file line number Diff line number Diff line change
Expand Up @@ -193,15 +193,15 @@ public List<PhotonPipelineResult> getAllUnreadResults() {
// make time sync more reliable.
for (var c : changes) {
var result = c.value;
result.setRecieveTimestampMicros(c.timestamp);
result.setReceiveTimestampMicros(c.timestamp);
ret.add(result);
}

return ret;
}

/**
* Returns the latest pipeline result. This is simply the most recent result recieved via NT.
* Returns the latest pipeline result. This is simply the most recent result Received via NT.
* Calling this multiple times will always return the most recent result.
*
* <p>Replaced by {@link #getAllUnreadResults()} over getLatestResult, as this function can miss
Expand All @@ -221,7 +221,7 @@ public PhotonPipelineResult getLatestResult() {
// contains a thing with time knowledge, set it here.
// getLatestChange returns in microseconds, so we divide by 1e6 to convert to seconds.
// TODO: NT4 time sync is Not To Be Trusted, we should do something else?
result.setRecieveTimestampMicros(ret.timestamp);
result.setReceiveTimestampMicros(ret.timestamp);

return result;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -554,7 +554,7 @@ public PhotonPipelineResult process(
now,
detectableTgts,
multitagResult);
ret.setRecieveTimestampMicros(now);
ret.setReceiveTimestampMicros(now);
return ret;
}

Expand Down
4 changes: 2 additions & 2 deletions photon-lib/src/main/native/cpp/photon/PhotonCamera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ PhotonPipelineResult PhotonCamera::GetLatestResult() {
// Create the new result;
PhotonPipelineResult result = packet.Unpack<PhotonPipelineResult>();

result.SetRecieveTimestamp(now);
result.SetReceiveTimestamp(now);

return result;
}
Expand Down Expand Up @@ -165,7 +165,7 @@ std::vector<PhotonPipelineResult> PhotonCamera::GetAllUnreadResults() {

// TODO: NT4 timestamps are still not to be trusted. But it's the best we
// can do until we can make time sync more reliable.
result.SetRecieveTimestamp(units::microsecond_t(value.time) -
result.SetReceiveTimestamp(units::microsecond_t(value.time) -
result.GetLatency());

ret.push_back(result);
Expand Down
9 changes: 5 additions & 4 deletions photon-lib/src/main/native/cpp/photon/PhotonPoseEstimator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,8 @@ std::optional<EstimatedRobotPose> PhotonPoseEstimator::Update(
std::optional<PhotonCamera::DistortionMatrix> cameraDistCoeffs) {
// Time in the past -- give up, since the following if expects times > 0
if (result.GetTimestamp() < 0_s) {
FRC_ReportError(frc::warn::Warning,
"Result timestamp was reported in the past!");
return std::nullopt;
}

Expand Down Expand Up @@ -164,7 +166,7 @@ std::optional<EstimatedRobotPose> PhotonPoseEstimator::Update(
}

if (ret) {
lastPose = ret.value().estimatedPose;
lastPose = ret->estimatedPose;
}
return ret;
}
Expand Down Expand Up @@ -197,8 +199,7 @@ std::optional<EstimatedRobotPose> PhotonPoseEstimator::LowestAmbiguityStrategy(
}

return EstimatedRobotPose{
fiducialPose.value()
.TransformBy(bestTarget.GetBestCameraToTarget().Inverse())
fiducialPose->TransformBy(bestTarget.GetBestCameraToTarget().Inverse())
.TransformBy(m_robotToCamera.Inverse()),
result.GetTimestamp(), result.GetTargets(), LOWEST_AMBIGUITY};
}
Expand All @@ -220,7 +221,7 @@ PhotonPoseEstimator::ClosestToCameraHeightStrategy(
target.GetFiducialId());
continue;
}
frc::Pose3d const targetPose = fiducialPose.value();
frc::Pose3d const targetPose = *fiducialPose;

units::meter_t const alternativeDifference = units::math::abs(
m_robotToCamera.Z() -
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -314,7 +314,7 @@ PhotonPipelineResult PhotonCameraSim::Process(
VisionEstimation::GetVisibleLayoutTags(detectableTgts, tagLayout);
if (visibleLayoutTags.size() > 1) {
std::vector<int16_t> usedIds{};
usedIds.reserve(32);
usedIds.resize(visibleLayoutTags.size());
std::transform(visibleLayoutTags.begin(), visibleLayoutTags.end(),
usedIds.begin(),
[](const frc::AprilTag& tag) { return tag.ID; });
Expand All @@ -337,52 +337,52 @@ void PhotonCameraSim::SubmitProcessedFrame(const PhotonPipelineResult& result) {
SubmitProcessedFrame(result, wpi::Now());
}
void PhotonCameraSim::SubmitProcessedFrame(const PhotonPipelineResult& result,
uint64_t recieveTimestamp) {
uint64_t ReceiveTimestamp) {
ts.latencyMillisEntry.Set(
result.GetLatency().convert<units::milliseconds>().to<double>(),
recieveTimestamp);
ReceiveTimestamp);

Packet newPacket{};
newPacket.Pack(result);

ts.rawBytesEntry.Set(newPacket.GetData(), recieveTimestamp);
ts.rawBytesEntry.Set(newPacket.GetData(), ReceiveTimestamp);

bool hasTargets = result.HasTargets();
ts.hasTargetEntry.Set(hasTargets, recieveTimestamp);
ts.hasTargetEntry.Set(hasTargets, ReceiveTimestamp);
if (!hasTargets) {
ts.targetPitchEntry.Set(0.0, recieveTimestamp);
ts.targetYawEntry.Set(0.0, recieveTimestamp);
ts.targetAreaEntry.Set(0.0, recieveTimestamp);
ts.targetPitchEntry.Set(0.0, ReceiveTimestamp);
ts.targetYawEntry.Set(0.0, ReceiveTimestamp);
ts.targetAreaEntry.Set(0.0, ReceiveTimestamp);
std::array<double, 3> poseData{0.0, 0.0, 0.0};
ts.targetPoseEntry.Set(poseData, recieveTimestamp);
ts.targetSkewEntry.Set(0.0, recieveTimestamp);
ts.targetPoseEntry.Set(poseData, ReceiveTimestamp);
ts.targetSkewEntry.Set(0.0, ReceiveTimestamp);
} else {
PhotonTrackedTarget bestTarget = result.GetBestTarget();

ts.targetPitchEntry.Set(bestTarget.GetPitch(), recieveTimestamp);
ts.targetYawEntry.Set(bestTarget.GetYaw(), recieveTimestamp);
ts.targetAreaEntry.Set(bestTarget.GetArea(), recieveTimestamp);
ts.targetSkewEntry.Set(bestTarget.GetSkew(), recieveTimestamp);
ts.targetPitchEntry.Set(bestTarget.GetPitch(), ReceiveTimestamp);
ts.targetYawEntry.Set(bestTarget.GetYaw(), ReceiveTimestamp);
ts.targetAreaEntry.Set(bestTarget.GetArea(), ReceiveTimestamp);
ts.targetSkewEntry.Set(bestTarget.GetSkew(), ReceiveTimestamp);

frc::Transform3d transform = bestTarget.GetBestCameraToTarget();
std::array<double, 4> poseData{
transform.X().to<double>(), transform.Y().to<double>(),
transform.Rotation().ToRotation2d().Degrees().to<double>()};
ts.targetPoseEntry.Set(poseData, recieveTimestamp);
ts.targetPoseEntry.Set(poseData, ReceiveTimestamp);
}

Eigen::Matrix<double, 3, 3, Eigen::RowMajor> intrinsics =
prop.GetIntrinsics();
std::span<double> intrinsicsView{intrinsics.data(),
intrinsics.data() + intrinsics.size()};
ts.cameraIntrinsicsPublisher.Set(intrinsicsView, recieveTimestamp);
ts.cameraIntrinsicsPublisher.Set(intrinsicsView, ReceiveTimestamp);

auto distortion = prop.GetDistCoeffs();
std::vector<double> distortionView{distortion.data(),
distortion.data() + distortion.size()};
ts.cameraDistortionPublisher.Set(distortionView, recieveTimestamp);
ts.cameraDistortionPublisher.Set(distortionView, ReceiveTimestamp);

ts.heartbeatPublisher.Set(heartbeatCounter, recieveTimestamp);
ts.heartbeatPublisher.Set(heartbeatCounter, ReceiveTimestamp);

ts.subTable->GetInstance().Flush();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ class PhotonCameraSim {

void SubmitProcessedFrame(const PhotonPipelineResult& result);
void SubmitProcessedFrame(const PhotonPipelineResult& result,
uint64_t recieveTimestamp);
uint64_t ReceiveTimestamp);

SimCameraProperties prop;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ void testLowestAmbiguityStrategy() {
new TargetCorner(3, 4),
new TargetCorner(5, 6),
new TargetCorner(7, 8)))));
cameraOne.result.setRecieveTimestampMicros((long) (11 * 1e6));
cameraOne.result.setReceiveTimestampMicros((long) (11 * 1e6));

PhotonPoseEstimator estimator =
new PhotonPoseEstimator(aprilTags, PoseStrategy.LOWEST_AMBIGUITY, new Transform3d());
Expand Down Expand Up @@ -217,7 +217,7 @@ void testClosestToCameraHeightStrategy() {
new TargetCorner(5, 6),
new TargetCorner(7, 8)))));

cameraOne.result.setRecieveTimestampMicros((long) (4 * 1e6));
cameraOne.result.setReceiveTimestampMicros((long) (4 * 1e6));

PhotonPoseEstimator estimator =
new PhotonPoseEstimator(
Expand Down Expand Up @@ -306,7 +306,7 @@ void closestToReferencePoseStrategy() {
new TargetCorner(3, 4),
new TargetCorner(5, 6),
new TargetCorner(7, 8)))));
cameraOne.result.setRecieveTimestampMicros((long) (17 * 1e6));
cameraOne.result.setReceiveTimestampMicros((long) (17 * 1e6));

PhotonPoseEstimator estimator =
new PhotonPoseEstimator(
Expand Down Expand Up @@ -396,7 +396,7 @@ void closestToLastPose() {
new TargetCorner(3, 4),
new TargetCorner(5, 6),
new TargetCorner(7, 8)))));
cameraOne.result.setRecieveTimestampMicros((long) (1 * 1e6));
cameraOne.result.setReceiveTimestampMicros((long) (1 * 1e6));

PhotonPoseEstimator estimator =
new PhotonPoseEstimator(
Expand Down Expand Up @@ -478,7 +478,7 @@ void closestToLastPose() {
new TargetCorner(3, 4),
new TargetCorner(5, 6),
new TargetCorner(7, 8)))));
cameraOne.result.setRecieveTimestampMicros((long) (7 * 1e6));
cameraOne.result.setReceiveTimestampMicros((long) (7 * 1e6));

estimatedPose = estimator.update(cameraOne.result);
pose = estimatedPose.get().estimatedPose;
Expand Down Expand Up @@ -519,7 +519,7 @@ void cacheIsInvalidated() {
new TargetCorner(3, 4),
new TargetCorner(5, 6),
new TargetCorner(7, 8)))));
result.setRecieveTimestampMicros((long) (20 * 1e6));
result.setReceiveTimestampMicros((long) (20 * 1e6));

PhotonPoseEstimator estimator =
new PhotonPoseEstimator(
Expand All @@ -529,7 +529,7 @@ void cacheIsInvalidated() {

// Empty result, expect empty result
cameraOne.result = new PhotonPipelineResult();
cameraOne.result.setRecieveTimestampMicros((long) (1 * 1e6));
cameraOne.result.setReceiveTimestampMicros((long) (1 * 1e6));
Optional<EstimatedRobotPose> estimatedPose = estimator.update(cameraOne.result);
assertFalse(estimatedPose.isPresent());

Expand Down Expand Up @@ -629,7 +629,7 @@ void averageBestPoses() {
new TargetCorner(3, 4),
new TargetCorner(5, 6),
new TargetCorner(7, 8))))); // 3 3 3 ambig .4
cameraOne.result.setRecieveTimestampMicros(20 * 1000000);
cameraOne.result.setReceiveTimestampMicros(20 * 1000000);

PhotonPoseEstimator estimator =
new PhotonPoseEstimator(
Expand Down
Loading

0 comments on commit 55dad98

Please sign in to comment.