27#include <frc/geometry/Pose2d.h>
28#include <frc/geometry/Rotation2d.h>
29#include <frc/geometry/Transform2d.h>
30#include <frc/geometry/Translation2d.h>
31#include <units/angle.h>
32#include <units/length.h>
33#include <units/math.h>
60 units::meter_t targetHeight,
61 units::radian_t cameraPitch,
62 units::radian_t targetPitch) {
63 return (targetHeight - cameraHeight) /
64 units::math::tan(cameraPitch + targetPitch);
76 units::meter_t targetDistance,
const frc::Rotation2d& yaw) {
77 return {targetDistance * yaw.Cos(), targetDistance * yaw.Sin()};
108 units::meter_t cameraHeight, units::meter_t targetHeight,
109 units::radian_t cameraPitch, units::radian_t targetPitch,
110 const frc::Rotation2d& targetYaw,
const frc::Rotation2d& gyroAngle,
111 const frc::Pose2d& fieldToTarget,
const frc::Transform2d& cameraToRobot) {
116 cameraPitch, targetPitch),
118 fieldToTarget, gyroAngle),
119 fieldToTarget, cameraToRobot);
139 const frc::Translation2d& cameraToTargetTranslation,
140 const frc::Pose2d& fieldToTarget,
const frc::Rotation2d& gyroAngle) {
145 return frc::Transform2d(cameraToTargetTranslation,
146 -gyroAngle - fieldToTarget.Rotation());
163 const frc::Transform2d& cameraToTarget,
const frc::Pose2d& fieldToTarget,
164 const frc::Transform2d& cameraToRobot) {
166 .TransformBy(cameraToRobot);
180 const frc::Transform2d& cameraToTarget,
181 const frc::Pose2d& fieldToTarget) {
182 auto targetToCamera = cameraToTarget.Inverse();
183 return fieldToTarget.TransformBy(targetToCamera);
Definition PhotonUtils.h:42
static frc::Pose2d EstimateFieldToRobot(const frc::Transform2d &cameraToTarget, const frc::Pose2d &fieldToTarget, const frc::Transform2d &cameraToRobot)
Estimates the pose of the robot in the field coordinate system, given the position of the target rela...
Definition PhotonUtils.h:162
static frc::Pose2d EstimateFieldToCamera(const frc::Transform2d &cameraToTarget, const frc::Pose2d &fieldToTarget)
Estimates the pose of the camera in the field coordinate system, given the position of the target rel...
Definition PhotonUtils.h:179
static frc::Transform2d EstimateCameraToTarget(const frc::Translation2d &cameraToTargetTranslation, const frc::Pose2d &fieldToTarget, const frc::Rotation2d &gyroAngle)
Estimates a frc::Transform2d that maps the camera position to the target position,...
Definition PhotonUtils.h:138
static units::meter_t CalculateDistanceToTarget(units::meter_t cameraHeight, units::meter_t targetHeight, units::radian_t cameraPitch, units::radian_t targetPitch)
Algorithm from https://docs.limelightvision.io/en/latest/cs_estimating_distance.html Estimates range ...
Definition PhotonUtils.h:59
static frc::Translation2d EstimateCameraToTargetTranslation(units::meter_t targetDistance, const frc::Rotation2d &yaw)
Estimate the Translation2d of the target relative to the camera.
Definition PhotonUtils.h:75
static frc::Pose2d EstimateFieldToRobot(units::meter_t cameraHeight, units::meter_t targetHeight, units::radian_t cameraPitch, units::radian_t targetPitch, const frc::Rotation2d &targetYaw, const frc::Rotation2d &gyroAngle, const frc::Pose2d &fieldToTarget, const frc::Transform2d &cameraToRobot)
Estimate the position of the robot in the field.
Definition PhotonUtils.h:107
Definition VisionEstimation.h:32