PhotonVision C++ dev-v2025.0.0-beta-8-2-gbd1c5c03
Loading...
Searching...
No Matches
PhotonUtils.h
Go to the documentation of this file.
1/*
2 * MIT License
3 *
4 * Copyright (c) PhotonVision
5 *
6 * Permission is hereby granted, free of charge, to any person obtaining a copy
7 * of this software and associated documentation files (the "Software"), to deal
8 * in the Software without restriction, including without limitation the rights
9 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
10 * copies of the Software, and to permit persons to whom the Software is
11 * furnished to do so, subject to the following conditions:
12 *
13 * The above copyright notice and this permission notice shall be included in
14 * all copies or substantial portions of the Software.
15 *
16 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
17 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
18 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
19 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
20 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
21 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
22 * SOFTWARE.
23 */
24
25#pragma once
26
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>
34
40
41namespace photon {
43 public:
44 /**
45 * Algorithm from
46 * https://docs.limelightvision.io/en/latest/cs_estimating_distance.html
47 * Estimates range to a target using the target's elevation. This method can
48 * produce more stable results than SolvePNP when well tuned, if the full 6d
49 * robot pose is not required.
50 *
51 * @param cameraHeight The height of the camera off the floor.
52 * @param targetHeight The height of the target off the floor.
53 * @param cameraPitch The pitch of the camera from the horizontal plane.
54 * Positive valueBytes up.
55 * @param targetPitch The pitch of the target in the camera's lens. Positive
56 * values up.
57 * @return The estimated distance to the target.
58 */
59 static units::meter_t CalculateDistanceToTarget(units::meter_t cameraHeight,
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);
65 }
66
67 /**
68 * Estimate the Translation2d of the target relative to the camera.
69 *
70 * @param targetDistance The distance to the target.
71 * @param yaw The observed yaw of the target.
72 *
73 * @return The target's camera-relative translation.
74 */
75 static frc::Translation2d EstimateCameraToTargetTranslation(
76 units::meter_t targetDistance, const frc::Rotation2d& yaw) {
77 return {targetDistance * yaw.Cos(), targetDistance * yaw.Sin()};
78 }
79
80 /**
81 * Estimate the position of the robot in the field.
82 *
83 * @param cameraHeightMeters The physical height of the camera off the floor
84 * in meters.
85 * @param targetHeightMeters The physical height of the target off the floor
86 * in meters. This should be the height of whatever is being targeted (i.e. if
87 * the targeting region is set to top, this should be the height of the top of
88 * the target).
89 * @param cameraPitchRadians The pitch of the camera from the horizontal plane
90 * in radians. Positive values up.
91 * @param targetPitchRadians The pitch of the target in the camera's lens in
92 * radians. Positive values up.
93 * @param targetYaw The observed yaw of the target. Note that this
94 * *must* be CCW-positive, and Photon returns
95 * CW-positive.
96 * @param gyroAngle The current robot gyro angle, likely from
97 * odometry.
98 * @param fieldToTarget A frc::Pose2d representing the target position in
99 * the field coordinate system.
100 * @param cameraToRobot The position of the robot relative to the camera.
101 * If the camera was mounted 3 inches behind the
102 * "origin" (usually physical center) of the robot,
103 * this would be frc::Transform2d(3 inches, 0
104 * inches, 0 degrees).
105 * @return The position of the robot in the field.
106 */
107 static frc::Pose2d EstimateFieldToRobot(
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) {
115 CalculateDistanceToTarget(cameraHeight, targetHeight,
116 cameraPitch, targetPitch),
117 targetYaw),
118 fieldToTarget, gyroAngle),
119 fieldToTarget, cameraToRobot);
120 }
121
122 /**
123 * Estimates a {@link frc::Transform2d} that maps the camera position to the
124 * target position, using the robot's gyro. Note that the gyro angle provided
125 * *must* line up with the field coordinate system -- that is, it should read
126 * zero degrees when pointed towards the opposing alliance station, and
127 * increase as the robot rotates CCW.
128 *
129 * @param cameraToTargetTranslation A Translation2d that encodes the x/y
130 * position of the target relative to the
131 * camera.
132 * @param fieldToTarget A frc::Pose2d representing the target
133 * position in the field coordinate system.
134 * @param gyroAngle The current robot gyro angle, likely from
135 * odometry.
136 * @return A frc::Transform2d that takes us from the camera to the target.
137 */
138 static frc::Transform2d EstimateCameraToTarget(
139 const frc::Translation2d& cameraToTargetTranslation,
140 const frc::Pose2d& fieldToTarget, const frc::Rotation2d& gyroAngle) {
141 // This pose maps our camera at the origin out to our target, in the robot
142 // reference frame
143 // The translation part of this frc::Transform2d is from the above step, and
144 // the rotation uses our robot's gyro.
145 return frc::Transform2d(cameraToTargetTranslation,
146 -gyroAngle - fieldToTarget.Rotation());
147 }
148
149 /**
150 * Estimates the pose of the robot in the field coordinate system, given the
151 * position of the target relative to the camera, the target relative to the
152 * field, and the robot relative to the camera.
153 *
154 * @param cameraToTarget The position of the target relative to the camera.
155 * @param fieldToTarget The position of the target in the field.
156 * @param cameraToRobot The position of the robot relative to the camera. If
157 * the camera was mounted 3 inches behind the "origin"
158 * (usually physical center) of the robot, this would be
159 * frc::Transform2d(3 inches, 0 inches, 0 degrees).
160 * @return The position of the robot in the field.
161 */
162 static frc::Pose2d EstimateFieldToRobot(
163 const frc::Transform2d& cameraToTarget, const frc::Pose2d& fieldToTarget,
164 const frc::Transform2d& cameraToRobot) {
165 return EstimateFieldToCamera(cameraToTarget, fieldToTarget)
166 .TransformBy(cameraToRobot);
167 }
168
169 /**
170 * Estimates the pose of the camera in the field coordinate system, given the
171 * position of the target relative to the camera, and the target relative to
172 * the field. This *only* tracks the position of the camera, not the position
173 * of the robot itself.
174 *
175 * @param cameraToTarget The position of the target relative to the camera.
176 * @param fieldToTarget The position of the target in the field.
177 * @return The position of the camera in the field.
178 */
179 static frc::Pose2d EstimateFieldToCamera(
180 const frc::Transform2d& cameraToTarget,
181 const frc::Pose2d& fieldToTarget) {
182 auto targetToCamera = cameraToTarget.Inverse();
183 return fieldToTarget.TransformBy(targetToCamera);
184 }
185};
186} // namespace photon
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