Skip to content

Commit 8676649

Browse files
Add PNP_DISTANCE_TRIG_SOLVE strategy to C++ (#2021)
1 parent 35dcc3c commit 8676649

File tree

3 files changed

+202
-1
lines changed

3 files changed

+202
-1
lines changed

photon-lib/src/main/native/cpp/photon/PhotonPoseEstimator.cpp

Lines changed: 53 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@
4444
#include <opencv2/calib3d.hpp>
4545
#include <opencv2/core/mat.hpp>
4646
#include <opencv2/core/types.hpp>
47+
#include <units/angle.h>
4748
#include <units/math.h>
4849
#include <units/time.h>
4950

@@ -73,7 +74,8 @@ PhotonPoseEstimator::PhotonPoseEstimator(frc::AprilTagFieldLayout tags,
7374
m_robotToCamera(robotToCamera),
7475
lastPose(frc::Pose3d()),
7576
referencePose(frc::Pose3d()),
76-
poseCacheTimestamp(-1_s) {
77+
poseCacheTimestamp(-1_s),
78+
headingBuffer(frc::TimeInterpolatableBuffer<frc::Rotation2d>(1_s)) {
7779
HAL_Report(HALUsageReporting::kResourceType_PhotonPoseEstimator,
7880
InstanceCount);
7981
InstanceCount++;
@@ -159,6 +161,9 @@ std::optional<EstimatedRobotPose> PhotonPoseEstimator::Update(
159161
"");
160162
}
161163
break;
164+
case PNP_DISTANCE_TRIG_SOLVE:
165+
ret = PnpDistanceTrigSolveStrategy(result);
166+
break;
162167
default:
163168
FRC_ReportError(frc::warn::Warning, "Invalid Pose Strategy selected!",
164169
"");
@@ -429,6 +434,53 @@ std::optional<EstimatedRobotPose> PhotonPoseEstimator::MultiTagOnRioStrategy(
429434
MULTI_TAG_PNP_ON_RIO);
430435
}
431436

437+
std::optional<EstimatedRobotPose>
438+
PhotonPoseEstimator::PnpDistanceTrigSolveStrategy(PhotonPipelineResult result) {
439+
PhotonTrackedTarget bestTarget = result.GetBestTarget();
440+
std::optional<frc::Rotation2d> headingSampleOpt =
441+
headingBuffer.Sample(result.GetTimestamp());
442+
if (!headingSampleOpt) {
443+
FRC_ReportError(frc::warn::Warning,
444+
"There was no heading data! Use AddHeadingData to add it!");
445+
return std::nullopt;
446+
}
447+
448+
frc::Rotation2d headingSample = headingSampleOpt.value();
449+
450+
frc::Translation2d camToTagTranslation =
451+
frc::Translation3d(
452+
bestTarget.GetBestCameraToTarget().Translation().Norm(),
453+
frc::Rotation3d(0_rad, -units::degree_t(bestTarget.GetPitch()),
454+
-units::degree_t(bestTarget.GetYaw())))
455+
.RotateBy(m_robotToCamera.Rotation())
456+
.ToTranslation2d()
457+
.RotateBy(headingSample);
458+
459+
std::optional<frc::Pose3d> fiducialPose =
460+
aprilTags.GetTagPose(bestTarget.GetFiducialId());
461+
if (!fiducialPose) {
462+
FRC_ReportError(frc::warn::Warning,
463+
"Tried to get pose of unknown April Tag: {}",
464+
bestTarget.GetFiducialId());
465+
return std::nullopt;
466+
}
467+
468+
frc::Pose2d tagPose = fiducialPose.value().ToPose2d();
469+
470+
frc::Translation2d fieldToCameraTranslation =
471+
tagPose.Translation() - camToTagTranslation;
472+
473+
frc::Translation2d camToRobotTranslation =
474+
(-m_robotToCamera.Translation().ToTranslation2d())
475+
.RotateBy(headingSample);
476+
477+
frc::Pose2d robotPose = frc::Pose2d(
478+
fieldToCameraTranslation + camToRobotTranslation, headingSample);
479+
480+
return EstimatedRobotPose{frc::Pose3d(robotPose), result.GetTimestamp(),
481+
result.GetTargets(), PNP_DISTANCE_TRIG_SOLVE};
482+
}
483+
432484
std::optional<EstimatedRobotPose>
433485
PhotonPoseEstimator::AverageBestTargetsStrategy(PhotonPipelineResult result) {
434486
std::vector<std::pair<frc::Pose3d, std::pair<double, units::second_t>>>

photon-lib/src/main/native/include/photon/PhotonPoseEstimator.h

Lines changed: 69 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@
2929
#include <frc/apriltag/AprilTagFieldLayout.h>
3030
#include <frc/geometry/Pose3d.h>
3131
#include <frc/geometry/Transform3d.h>
32+
#include <frc/interpolation/TimeInterpolatableBuffer.h>
3233
#include <opencv2/core/mat.hpp>
3334

3435
#include "photon/PhotonCamera.h"
@@ -47,6 +48,7 @@ enum PoseStrategy {
4748
AVERAGE_BEST_TARGETS,
4849
MULTI_TAG_PNP_ON_COPROCESSOR,
4950
MULTI_TAG_PNP_ON_RIO,
51+
PNP_DISTANCE_TRIG_SOLVE,
5052
};
5153

5254
struct EstimatedRobotPose {
@@ -172,6 +174,61 @@ class PhotonPoseEstimator {
172174
*/
173175
inline void SetLastPose(frc::Pose3d lastPose) { this->lastPose = lastPose; }
174176

177+
/**
178+
* Add robot heading data to the buffer. Must be called periodically for the
179+
* PNP_DISTANCE_TRIG_SOLVE strategy.
180+
*
181+
* @param timestamp Timestamp of the robot heading data.
182+
* @param heading Field-relative heading at the given timestamp. Standard
183+
* WPILIB field coordinates.
184+
*/
185+
inline void AddHeadingData(units::second_t timestamp,
186+
frc::Rotation2d heading) {
187+
this->headingBuffer.AddSample(timestamp, heading);
188+
}
189+
190+
/**
191+
* Add robot heading data to the buffer. Must be called periodically for the
192+
* PNP_DISTANCE_TRIG_SOLVE strategy.
193+
*
194+
* @param timestamp Timestamp of the robot heading data.
195+
* @param heading Field-relative heading at the given timestamp. Standard
196+
* WPILIB coordinates.
197+
*/
198+
inline void AddHeadingData(units::second_t timestamp,
199+
frc::Rotation3d heading) {
200+
AddHeadingData(timestamp, heading.ToRotation2d());
201+
}
202+
203+
/**
204+
* Clears all heading data in the buffer, and adds a new seed. Useful for
205+
* preventing estimates from utilizing heading data provided prior to a pose
206+
* or rotation reset.
207+
*
208+
* @param timestamp Timestamp of the robot heading data.
209+
* @param heading Field-relative robot heading at given timestamp. Standard
210+
* WPILIB field coordinates.
211+
*/
212+
inline void ResetHeadingData(units::second_t timestamp,
213+
frc::Rotation2d heading) {
214+
headingBuffer.Clear();
215+
AddHeadingData(timestamp, heading);
216+
}
217+
218+
/**
219+
* Clears all heading data in the buffer, and adds a new seed. Useful for
220+
* preventing estimates from utilizing heading data provided prior to a pose
221+
* or rotation reset.
222+
*
223+
* @param timestamp Timestamp of the robot heading data.
224+
* @param heading Field-relative robot heading at given timestamp. Standard
225+
* WPILIB field coordinates.
226+
*/
227+
inline void ResetHeadingData(units::second_t timestamp,
228+
frc::Rotation3d heading) {
229+
ResetHeadingData(timestamp, heading.ToRotation2d());
230+
}
231+
175232
/**
176233
* Update the pose estimator. If updating multiple times per loop, you should
177234
* call this exactly once per new result, in order of increasing result
@@ -200,6 +257,8 @@ class PhotonPoseEstimator {
200257

201258
units::second_t poseCacheTimestamp;
202259

260+
frc::TimeInterpolatableBuffer<frc::Rotation2d> headingBuffer;
261+
203262
inline static int InstanceCount = 1;
204263

205264
inline void InvalidatePoseCache() { poseCacheTimestamp = -1_s; }
@@ -278,6 +337,16 @@ class PhotonPoseEstimator {
278337
std::optional<PhotonCamera::CameraMatrix> camMat,
279338
std::optional<PhotonCamera::DistortionMatrix> distCoeffs);
280339

340+
/**
341+
* Return the pose calculation using the best visible tag and the robot's
342+
* heading
343+
*
344+
* @return the estimated position of the robot in the FCS and the estimated
345+
* timestamp of this estimation
346+
*/
347+
std::optional<EstimatedRobotPose> PnpDistanceTrigSolveStrategy(
348+
PhotonPipelineResult result);
349+
281350
/**
282351
* Return the average of the best target poses using ambiguity as weight.
283352

photon-lib/src/test/native/cpp/PhotonPoseEstimatorTest.cpp

Lines changed: 80 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,8 @@
3838
#include "photon/PhotonCamera.h"
3939
#include "photon/PhotonPoseEstimator.h"
4040
#include "photon/dataflow/structures/Packet.h"
41+
#include "photon/simulation/PhotonCameraSim.h"
42+
#include "photon/simulation/SimCameraProperties.h"
4143
#include "photon/targeting/MultiTargetPNPResult.h"
4244
#include "photon/targeting/PhotonPipelineResult.h"
4345
#include "photon/targeting/PhotonTrackedTarget.h"
@@ -306,6 +308,84 @@ TEST(PhotonPoseEstimatorTest, ClosestToLastPose) {
306308
EXPECT_NEAR(1, units::unit_cast<double>(pose.Z()), .01);
307309
}
308310

311+
TEST(PhotonPoseEstimatorTest, PnpDistanceTrigSolve) {
312+
photon::PhotonCamera cameraOne = photon::PhotonCamera("test");
313+
cameraOne.test = true;
314+
315+
std::vector<photon::VisionTargetSim> targets;
316+
targets.reserve(tags.size());
317+
for (const auto& tag : tags) {
318+
targets.push_back(
319+
photon::VisionTargetSim(tag.pose, photon::kAprilTag36h11, tag.ID));
320+
}
321+
photon::PhotonCameraSim cameraOneSim = photon::PhotonCameraSim(
322+
&cameraOne, photon::SimCameraProperties::PERFECT_90DEG());
323+
324+
/* Compound Rolled + Pitched + Yaw */
325+
frc::Transform3d compoundTestTransform = frc::Transform3d(
326+
-12_in, -11_in, 3_m, frc::Rotation3d(37_deg, 6_deg, 60_deg));
327+
328+
photon::PhotonPoseEstimator estimator(
329+
aprilTags, photon::PNP_DISTANCE_TRIG_SOLVE, compoundTestTransform);
330+
331+
/* real pose of the robot base to test against */
332+
frc::Pose3d realPose =
333+
frc::Pose3d(7.3_m, 4.42_m, 0_m, frc::Rotation3d(0_rad, 0_rad, 2.197_rad));
334+
335+
photon::PhotonPipelineResult result = cameraOneSim.Process(
336+
1_ms, realPose.TransformBy(estimator.GetRobotToCameraTransform()),
337+
targets);
338+
cameraOne.testResult = {result};
339+
cameraOne.testResult[0].SetReceiveTimestamp(17_s);
340+
341+
estimator.AddHeadingData(result.GetTimestamp(), realPose.Rotation());
342+
343+
std::optional<photon::EstimatedRobotPose> estimatedPose;
344+
for (const auto& result : cameraOne.GetAllUnreadResults()) {
345+
estimatedPose = estimator.Update(result);
346+
}
347+
348+
ASSERT_TRUE(estimatedPose);
349+
frc::Pose3d pose = estimatedPose.value().estimatedPose;
350+
351+
EXPECT_NEAR(units::unit_cast<double>(realPose.X()),
352+
units::unit_cast<double>(pose.X()), .01);
353+
EXPECT_NEAR(units::unit_cast<double>(realPose.Y()),
354+
units::unit_cast<double>(pose.Y()), .01);
355+
EXPECT_NEAR(units::unit_cast<double>(realPose.Z()),
356+
units::unit_cast<double>(pose.Z()), .01);
357+
358+
/* Straight on */
359+
frc::Transform3d straightOnTestTransform =
360+
frc::Transform3d(0_m, 0_m, 3_m, frc::Rotation3d(0_rad, 0_rad, 0_rad));
361+
362+
estimator.SetRobotToCameraTransform(straightOnTestTransform);
363+
realPose = frc::Pose3d(4.81_m, 2.38_m, 0_m,
364+
frc::Rotation3d(0_rad, 0_rad, 2.818_rad));
365+
result = cameraOneSim.Process(
366+
1_ms, realPose.TransformBy(estimator.GetRobotToCameraTransform()),
367+
targets);
368+
cameraOne.testResult = {result};
369+
cameraOne.testResult[0].SetReceiveTimestamp(18_s);
370+
371+
estimator.AddHeadingData(result.GetTimestamp(), realPose.Rotation());
372+
373+
estimatedPose = std::nullopt;
374+
for (const auto& result : cameraOne.GetAllUnreadResults()) {
375+
estimatedPose = estimator.Update(result);
376+
}
377+
378+
ASSERT_TRUE(estimatedPose);
379+
pose = estimatedPose.value().estimatedPose;
380+
381+
EXPECT_NEAR(units::unit_cast<double>(realPose.X()),
382+
units::unit_cast<double>(pose.X()), .01);
383+
EXPECT_NEAR(units::unit_cast<double>(realPose.Y()),
384+
units::unit_cast<double>(pose.Y()), .01);
385+
EXPECT_NEAR(units::unit_cast<double>(realPose.Z()),
386+
units::unit_cast<double>(pose.Z()), .01);
387+
}
388+
309389
TEST(PhotonPoseEstimatorTest, AverageBestPoses) {
310390
photon::PhotonCamera cameraOne = photon::PhotonCamera("test");
311391

0 commit comments

Comments
 (0)