Expose both pose solutions (#521)

* Half-add second pose

* add c++

* run wpiformat

* Fix c++
This commit is contained in:
Matt
2022-10-22 07:42:45 -04:00
committed by GitHub
parent 27198a3e32
commit 2d7a88e231
14 changed files with 142 additions and 63 deletions

View File

@@ -97,10 +97,22 @@ class PhotonTrackedTarget {
double GetPoseAmbiguity() const { return poseAmbiguity; }
/**
* Returns the pose of the target relative to the robot.
* Get the transform that maps camera space (X = forward, Y = left, Z = up) to
* object/fiducial tag space (X forward, Y left, Z up) with the lowest
* reprojection error. The ratio between this and the alternate target's
* reprojection error is the ambiguity, which is between 0 and 1.
* @return The pose of the target relative to the robot.
*/
frc::Transform3d GetCameraToTarget() const { return cameraToTarget; }
frc::Transform3d GetBestCameraToTarget() const { return bestCameraToTarget; }
/**
* Get the transform that maps camera space (X = forward, Y = left, Z = up) to
* object/fiducial tag space (X forward, Y left, Z up) with the highest
* reprojection error
*/
frc::Transform3d GetAlternateCameraToTarget() const {
return altCameraToTarget;
}
bool operator==(const PhotonTrackedTarget& other) const;
bool operator!=(const PhotonTrackedTarget& other) const;
@@ -114,7 +126,8 @@ class PhotonTrackedTarget {
double area = 0;
double skew = 0;
int fiducialId;
frc::Transform3d cameraToTarget;
frc::Transform3d bestCameraToTarget;
frc::Transform3d altCameraToTarget;
double poseAmbiguity;
wpi::SmallVector<std::pair<double, double>, 4> corners;
};