The PhotonPoseEstimator class filters or combines readings from all the fiducials visible at a given timestamp on the field to produce a single robot in field pose, using the strategy set below.
More...
#include <photon/PhotonPoseEstimator.h>
|
| | PhotonPoseEstimator (frc::AprilTagFieldLayout aprilTags, PoseStrategy strategy, frc::Transform3d robotToCamera) |
| | Create a new PhotonPoseEstimator.
|
| |
| frc::AprilTagFieldLayout | GetFieldLayout () const |
| | Get the AprilTagFieldLayout being used by the PositionEstimator.
|
| |
| PoseStrategy | GetPoseStrategy () const |
| | Get the Position Estimation Strategy being used by the Position Estimator.
|
| |
| void | SetPoseStrategy (PoseStrategy strat) |
| | Set the Position Estimation Strategy used by the Position Estimator.
|
| |
| void | SetMultiTagFallbackStrategy (PoseStrategy strategy) |
| | Set the Position Estimation Strategy used in multi-tag mode when only one tag can be seen.
|
| |
| frc::Pose3d | GetReferencePose () const |
| | Return the reference position that is being used by the estimator.
|
| |
| void | SetReferencePose (frc::Pose3d referencePose) |
| | Update the stored reference pose for use when using the CLOSEST_TO_REFERENCE_POSE strategy.
|
| |
| frc::Transform3d | GetRobotToCameraTransform () |
| |
| void | SetRobotToCameraTransform (frc::Transform3d robotToCamera) |
| | Useful for pan and tilt mechanisms, or cameras on turrets.
|
| |
| void | SetLastPose (frc::Pose3d lastPose) |
| | Update the stored last pose.
|
| |
| void | AddHeadingData (units::second_t timestamp, frc::Rotation2d heading) |
| | Add robot heading data to the buffer.
|
| |
| void | AddHeadingData (units::second_t timestamp, frc::Rotation3d heading) |
| | Add robot heading data to the buffer.
|
| |
| void | ResetHeadingData (units::second_t timestamp, frc::Rotation2d heading) |
| | Clears all heading data in the buffer, and adds a new seed.
|
| |
| void | ResetHeadingData (units::second_t timestamp, frc::Rotation3d heading) |
| | Clears all heading data in the buffer, and adds a new seed.
|
| |
| std::optional< EstimatedRobotPose > | Update (const photon::PhotonPipelineResult &result, std::optional< photon::PhotonCamera::CameraMatrix > cameraMatrixData=std::nullopt, std::optional< photon::PhotonCamera::DistortionMatrix > coeffsData=std::nullopt, std::optional< ConstrainedSolvepnpParams > constrainedPnpParams=std::nullopt) |
| | Update the pose estimator.
|
| |
The PhotonPoseEstimator class filters or combines readings from all the fiducials visible at a given timestamp on the field to produce a single robot in field pose, using the strategy set below.
Example usage can be found in our apriltagExample example project.
◆ PhotonPoseEstimator()
| photon::PhotonPoseEstimator::PhotonPoseEstimator |
( |
frc::AprilTagFieldLayout | aprilTags, |
|
|
PoseStrategy | strategy, |
|
|
frc::Transform3d | robotToCamera ) |
|
explicit |
Create a new PhotonPoseEstimator.
- Parameters
-
| aprilTags | A AprilTagFieldLayout linking AprilTag IDs to Pose3ds with respect to the FIRST field. |
| strategy | The strategy it should use to determine the best pose. |
| robotToCamera | Transform3d from the center of the robot to the camera mount positions (ie, robot ➔ camera). |
◆ AddHeadingData() [1/2]
| void photon::PhotonPoseEstimator::AddHeadingData |
( |
units::second_t | timestamp, |
|
|
frc::Rotation2d | heading ) |
|
inline |
Add robot heading data to the buffer.
Must be called periodically for the PNP_DISTANCE_TRIG_SOLVE strategy.
- Parameters
-
| timestamp | Timestamp of the robot heading data. |
| heading | Field-relative heading at the given timestamp. Standard WPILIB field coordinates. |
◆ AddHeadingData() [2/2]
| void photon::PhotonPoseEstimator::AddHeadingData |
( |
units::second_t | timestamp, |
|
|
frc::Rotation3d | heading ) |
|
inline |
Add robot heading data to the buffer.
Must be called periodically for the PNP_DISTANCE_TRIG_SOLVE strategy.
- Parameters
-
| timestamp | Timestamp of the robot heading data. |
| heading | Field-relative heading at the given timestamp. Standard WPILIB coordinates. |
◆ GetFieldLayout()
| frc::AprilTagFieldLayout photon::PhotonPoseEstimator::GetFieldLayout |
( |
| ) |
const |
|
inline |
Get the AprilTagFieldLayout being used by the PositionEstimator.
- Returns
- the AprilTagFieldLayout
◆ GetPoseStrategy()
| PoseStrategy photon::PhotonPoseEstimator::GetPoseStrategy |
( |
| ) |
const |
|
inline |
Get the Position Estimation Strategy being used by the Position Estimator.
- Returns
- the strategy
◆ GetReferencePose()
| frc::Pose3d photon::PhotonPoseEstimator::GetReferencePose |
( |
| ) |
const |
|
inline |
Return the reference position that is being used by the estimator.
- Returns
- the referencePose
◆ GetRobotToCameraTransform()
| frc::Transform3d photon::PhotonPoseEstimator::GetRobotToCameraTransform |
( |
| ) |
|
|
inline |
- Returns
- The current transform from the center of the robot to the camera mount position.
◆ ResetHeadingData() [1/2]
| void photon::PhotonPoseEstimator::ResetHeadingData |
( |
units::second_t | timestamp, |
|
|
frc::Rotation2d | heading ) |
|
inline |
Clears all heading data in the buffer, and adds a new seed.
Useful for preventing estimates from utilizing heading data provided prior to a pose or rotation reset.
- Parameters
-
| timestamp | Timestamp of the robot heading data. |
| heading | Field-relative robot heading at given timestamp. Standard WPILIB field coordinates. |
◆ ResetHeadingData() [2/2]
| void photon::PhotonPoseEstimator::ResetHeadingData |
( |
units::second_t | timestamp, |
|
|
frc::Rotation3d | heading ) |
|
inline |
Clears all heading data in the buffer, and adds a new seed.
Useful for preventing estimates from utilizing heading data provided prior to a pose or rotation reset.
- Parameters
-
| timestamp | Timestamp of the robot heading data. |
| heading | Field-relative robot heading at given timestamp. Standard WPILIB field coordinates. |
◆ SetLastPose()
| void photon::PhotonPoseEstimator::SetLastPose |
( |
frc::Pose3d | lastPose | ) |
|
|
inline |
Update the stored last pose.
Useful for setting the initial estimate when using the CLOSEST_TO_LAST_POSE strategy.
- Parameters
-
| lastPose | the lastPose to set |
◆ SetMultiTagFallbackStrategy()
| void photon::PhotonPoseEstimator::SetMultiTagFallbackStrategy |
( |
PoseStrategy | strategy | ) |
|
Set the Position Estimation Strategy used in multi-tag mode when only one tag can be seen.
Must NOT be MULTI_TAG_PNP
- Parameters
-
| strategy | the strategy to set |
◆ SetPoseStrategy()
| void photon::PhotonPoseEstimator::SetPoseStrategy |
( |
PoseStrategy | strat | ) |
|
|
inline |
Set the Position Estimation Strategy used by the Position Estimator.
- Parameters
-
| strategy | the strategy to set |
◆ SetReferencePose()
| void photon::PhotonPoseEstimator::SetReferencePose |
( |
frc::Pose3d | referencePose | ) |
|
|
inline |
Update the stored reference pose for use when using the CLOSEST_TO_REFERENCE_POSE strategy.
- Parameters
-
| referencePose | the referencePose to set |
◆ SetRobotToCameraTransform()
| void photon::PhotonPoseEstimator::SetRobotToCameraTransform |
( |
frc::Transform3d | robotToCamera | ) |
|
|
inline |
Useful for pan and tilt mechanisms, or cameras on turrets.
- Parameters
-
| robotToCamera | The current transform from the center of the robot to the camera mount position. |
◆ Update()
Update the pose estimator.
If updating multiple times per loop, you should call this exactly once per new result, in order of increasing result timestamp.
- Parameters
-
| result | The vision targeting result to process |
| cameraIntrinsics | The camera calibration pinhole coefficients matrix. Only required if doing multitag-on-rio, and may be nullopt otherwise. |
| distCoeffsData | The camera calibration distortion coefficients. Only required if doing multitag-on-rio, and may be nullopt otherwise. |
| constrainedPnpParams | Constrained SolvePNP params, if needed. |
The documentation for this class was generated from the following file: