CTRE Phoenix 6 C++ 25.0.0-beta-4
Loading...
Searching...
No Matches
SwerveDrivePoseEstimator.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) Cross The Road Electronics.  All rights reserved.
3 * License information can be found in CTRE_LICENSE.txt
4 * For support and suggestions contact support@ctr-electronics.com or file
5 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases
6 */
7#pragma once
8
12#include <array>
13#include <map>
14
15namespace ctre {
16namespace phoenix6 {
17namespace swerve {
18namespace impl {
19
20/**
21 * \brief Class for swerve drive odometry. Odometry allows you to track the robot's
22 * position on the field over a course of a match using readings from your
23 * swerve drive encoders and swerve azimuth encoders.
24 *
25 * Teams can use odometry during the autonomous period for complex tasks like
26 * path following. Furthermore, odometry can be used for latency compensation
27 * when using computer-vision systems.
28 */
30public:
31 using WheelSpeeds = std::vector<SwerveModuleState>;
32 using WheelPositions = std::vector<SwerveModulePosition>;
33
34private:
35 SwerveDriveKinematics const &m_kinematics;
36 Pose2d m_pose;
37
38 WheelPositions m_previousWheelPositions;
39 Rotation2d m_previousAngle;
40 Rotation2d m_gyroOffset;
41
42public:
43 /**
44 * \brief Constructs a SwerveDriveOdometry object.
45 *
46 * \param kinematics The swerve drive kinematics for your drivetrain.
47 * \param gyroAngle The angle reported by the gyroscope.
48 * \param modulePositions The wheel positions reported by each module.
49 * \param initialPose The starting position of the robot on the field.
50 */
51 SwerveDriveOdometry(SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle, WheelPositions modulePositions, Pose2d initialPose = Pose2d{}) :
52 m_kinematics{kinematics},
53 m_pose{std::move(initialPose)},
54 m_previousWheelPositions{std::move(modulePositions)},
55 m_previousAngle{m_pose.Rotation()},
56 m_gyroOffset{m_pose.Rotation() - gyroAngle}
57 {}
58
59 /**
60 * \brief Resets the robot's position on the field.
61 *
62 * The gyroscope angle does not need to be reset here on the user's robot
63 * code. The library automatically takes care of offsetting the gyro angle.
64 *
65 * \param gyroAngle The angle reported by the gyroscope.
66 * \param wheelPositions The current distances measured by each wheel.
67 * \param pose The position on the field that your robot is at.
68 */
69 void ResetPosition(Rotation2d const &gyroAngle, WheelPositions wheelPositions, Pose2d const &pose)
70 {
71 m_pose = pose;
72 m_previousAngle = m_pose.Rotation();
73 m_gyroOffset = m_pose.Rotation() - gyroAngle;
74 m_previousWheelPositions = std::move(wheelPositions);
75 }
76
77 /**
78 * \brief Resets the pose.
79 *
80 * \param pose The pose to reset to.
81 */
82 void ResetPose(Pose2d const &pose)
83 {
84 m_gyroOffset = m_gyroOffset + (pose.Rotation() - m_pose.Rotation());
85 m_pose = pose;
86 m_previousAngle = pose.Rotation();
87 }
88
89 /**
90 * \brief Resets the translation of the pose.
91 *
92 * \param translation The translation to reset to.
93 */
94 void ResetTranslation(Translation2d const &translation)
95 {
96 m_pose = Pose2d{translation, m_pose.Rotation()};
97 }
98
99 /**
100 * \brief Resets the rotation of the pose.
101 *
102 * \param rotation The rotation to reset to.
103 */
104 void ResetRotation(Rotation2d const &rotation)
105 {
106 m_gyroOffset = m_gyroOffset + (rotation - m_pose.Rotation());
107 m_pose = Pose2d{m_pose.Translation(), rotation};
108 m_previousAngle = rotation;
109 }
110
111 /**
112 * \brief Returns the position of the robot on the field.
113 *
114 * \returns The pose of the robot.
115 */
116 Pose2d const &Pose() const { return m_pose; }
117
118 /**
119 * \brief Updates the robot's position on the field using forward kinematics and
120 * integration of the pose over time. This method takes in an angle parameter
121 * which is used instead of the angular rate that is calculated from forward
122 * kinematics, in addition to the current distance measurement at each wheel.
123 *
124 * \param gyroAngle The angle reported by the gyroscope.
125 * \param wheelPositions The current distances measured by each wheel.
126 *
127 * \returns The new pose of the robot.
128 */
129 Pose2d const &Update(Rotation2d const &gyroAngle, WheelPositions wheelPositions);
130};
131
132/**
133 * \brief This class wraps Swerve Drive Odometry to fuse latency-compensated
134 * vision measurements with swerve drive encoder distance measurements. It is
135 * intended to be a drop-in for SwerveDriveOdometry.
136 *
137 * Update() should be called every robot loop.
138 *
139 * AddVisionMeasurement() can be called as infrequently as you want; if you
140 * never call it, then this class will behave as regular encoder odometry.
141 */
143public:
144 using WheelSpeeds = std::vector<SwerveModuleState>;
145 using WheelPositions = std::vector<SwerveModulePosition>;
146
147private:
148 struct VisionUpdate {
149 /** \brief The vision-compensated pose estimate */
150 Pose2d visionPose;
151
152 /** \brief The pose estimated based solely on odometry */
153 Pose2d odometryPose;
154
155 /**
156 * \brief Returns the vision-compensated version of the pose. Specifically, changes
157 * the pose from being relative to this record's odometry pose to being
158 * relative to this record's vision pose.
159 *
160 * \param pose The pose to compensate.
161 * \returns The compensated pose.
162 */
163 Pose2d Compensate(const Pose2d& pose) const
164 {
165 auto const delta = pose - odometryPose;
166 return visionPose + delta;
167 }
168 };
169
170 static constexpr units::second_t kBufferDuration = 1.5_s;
171
172 SwerveDriveOdometry m_odometry;
173 std::array<double, 3> m_q{};
174
175 struct VisionMatrices;
176 std::unique_ptr<VisionMatrices> m_matrices;
177
178 /* Maps timestamps to odometry-only pose estimates */
179 TimeInterpolatableBuffer<Pose2d> m_odometryPoseBuffer{kBufferDuration};
180 /*
181 * Maps timestamps to vision updates
182 * Always contains one entry before the oldest entry in m_odometryPoseBuffer,
183 * unless there have been no vision measurements after the last reset
184 */
185 std::map<units::second_t, VisionUpdate> m_visionUpdates;
186
187 Pose2d m_poseEstimate;
188
189 /**
190 * \brief Removes stale vision updates that won't affect sampling.
191 */
192 void CleanUpVisionUpdates();
193
194public:
195 /**
196 * \brief Constructs a SwerveDrivePoseEstimator with default standard deviations
197 * for the model and vision measurements.
198 *
199 * The default standard deviations of the model states are
200 * 0.1 meters for x, 0.1 meters for y, and 0.1 radians for heading.
201 * The default standard deviations of the vision measurements are
202 * 0.9 meters for x, 0.9 meters for y, and 0.9 radians for heading.
203 *
204 * \param kinematics A correctly-configured kinematics object for your
205 * drivetrain.
206 * \param gyroAngle The current gyro angle.
207 * \param modulePositions The current distance and rotation measurements of
208 * the swerve modules.
209 * \param initialPose The starting pose estimate.
210 */
211 SwerveDrivePoseEstimator(SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle,
212 WheelPositions modulePositions, Pose2d initialPose) :
213 SwerveDrivePoseEstimator{kinematics, gyroAngle, std::move(modulePositions), std::move(initialPose),
214 {0.1, 0.1, 0.1}, {0.9, 0.9, 0.9}}
215 {}
216
217 /**
218 * \brief Constructs a SwerveDrivePoseEstimator.
219 *
220 * \param kinematics A correctly-configured kinematics object for your
221 * drivetrain.
222 * \param gyroAngle The current gyro angle.
223 * \param modulePositions The current distance and rotation measurements of
224 * the swerve modules.
225 * \param initialPose The starting pose estimate.
226 * \param stateStdDevs Standard deviations of the pose estimate (x position in
227 * meters, y position in meters, and heading in radians). Increase these
228 * numbers to trust your state estimate less.
229 * \param visionMeasurementStdDevs Standard deviations of the vision pose
230 * measurement (x position in meters, y position in meters, and heading in
231 * radians). Increase these numbers to trust the vision pose measurement
232 * less.
233 */
234 SwerveDrivePoseEstimator(SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle,
235 WheelPositions modulePositions, Pose2d initialPose,
236 std::array<double, 3> const &stateStdDevs, std::array<double, 3> const &visionMeasurementStdDevs);
237
239
240 /**
241 * \brief Sets the pose estimator's trust in vision measurements. This might be used
242 * to change trust in vision measurements after the autonomous period, or to
243 * change trust as distance to a vision target increases.
244 *
245 * \param visionMeasurementStdDevs Standard deviations of the vision pose
246 * measurement (x position in meters, y position in meters, and heading in
247 * radians). Increase these numbers to trust the vision pose measurement
248 * less.
249 */
250 void SetVisionMeasurementStdDevs(std::array<double, 3> const &visionMeasurementStdDevs);
251
252 /**
253 * \brief Resets the robot's position on the field.
254 *
255 * The gyroscope angle does not need to be reset in the user's robot code.
256 * The library automatically takes care of offsetting the gyro angle.
257 *
258 * \param gyroAngle The current gyro angle.
259 * \param wheelPositions The distances traveled by the encoders.
260 * \param pose The estimated pose of the robot on the field.
261 */
262 void ResetPosition(Rotation2d const &gyroAngle, WheelPositions wheelPositions, Pose2d const &pose)
263 {
264 m_odometry.ResetPosition(gyroAngle, std::move(wheelPositions), pose);
265 m_odometryPoseBuffer.Clear();
266 m_visionUpdates.clear();
267 m_poseEstimate = m_odometry.Pose();
268 }
269
270 /**
271 * \brief Resets the robot's pose.
272 *
273 * \param pose The pose to reset to.
274 */
275 void ResetPose(Pose2d const &pose)
276 {
277 m_odometry.ResetPose(pose);
278 m_odometryPoseBuffer.Clear();
279 m_visionUpdates.clear();
280 m_poseEstimate = m_odometry.Pose();
281 }
282
283 /**
284 * \brief Resets the robot's translation.
285 *
286 * \param translation The pose to translation to.
287 */
288 void ResetTranslation(Translation2d const &translation)
289 {
290 m_odometry.ResetTranslation(translation);
291 m_odometryPoseBuffer.Clear();
292 m_visionUpdates.clear();
293 m_poseEstimate = m_odometry.Pose();
294 }
295
296 /**
297 * \brief Resets the robot's rotation.
298 *
299 * \param rotation The rotation to reset to.
300 */
301 void ResetRotation(Rotation2d const &rotation)
302 {
303 m_odometry.ResetRotation(rotation);
304 m_odometryPoseBuffer.Clear();
305 m_visionUpdates.clear();
306 m_poseEstimate = m_odometry.Pose();
307 }
308
309 /**
310 * \brief Gets the estimated robot pose.
311 *
312 * \returns The estimated robot pose in meters.
313 */
314 Pose2d GetEstimatedPosition() const
315 {
316 return m_poseEstimate;
317 }
318
319 /**
320 * \brief Return the pose at a given timestamp, if the buffer is not empty.
321 *
322 * \param timestamp The pose's timestamp.
323 * \returns The pose at the given timestamp (or std::nullopt if the buffer is
324 * empty).
325 */
326 std::optional<Pose2d> SampleAt(units::second_t timestamp) const;
327
328 /**
329 * \brief Adds a vision measurement to the Kalman Filter. This will correct
330 * the odometry pose estimate while still accounting for measurement noise.
331 *
332 * This method can be called as infrequently as you want, as long as you are
333 * calling Update() every loop.
334 *
335 * To promote stability of the pose estimate and make it robust to bad vision
336 * data, we recommend only adding vision measurements that are already within
337 * one meter or so of the current pose estimate.
338 *
339 * \param visionRobotPose The pose of the robot as measured by the vision
340 * camera.
341 * \param timestamp The timestamp of the vision measurement in seconds. Note
342 * that if you don't use your own time source by calling UpdateWithTime(),
343 * then you must use a timestamp with an epoch since system startup (i.e.,
344 * the epoch of this timestamp is the same epoch as utils#GetCurrentTime().
345 * This means that you should use utils#GetCurrentTime() as your time source
346 * in this case.
347 */
348 void AddVisionMeasurement(Pose2d const &visionRobotPose, units::second_t timestamp);
349
350 /**
351 * \brief Adds a vision measurement to the Kalman Filter. This will correct
352 * the odometry pose estimate while still accounting for measurement noise.
353 *
354 * This method can be called as infrequently as you want, as long as you are
355 * calling Update() every loop.
356 *
357 * To promote stability of the pose estimate and make it robust to bad vision
358 * data, we recommend only adding vision measurements that are already within
359 * one meter or so of the current pose estimate.
360 *
361 * Note that the vision measurement standard deviations passed into this
362 * method will continue to apply to future measurements until a subsequent
363 * call to SetVisionMeasurementStdDevs() or this method.
364 *
365 * \param visionRobotPose The pose of the robot as measured by the vision
366 * camera.
367 * \param timestamp The timestamp of the vision measurement in seconds. Note
368 * that if you don't use your own time source by calling UpdateWithTime(),
369 * then you must use a timestamp with an epoch since system startup (i.e.,
370 * the epoch of this timestamp is the same epoch as utils#GetCurrentTime().
371 * This means that you should use utils#GetCurrentTime() as your time source
372 * in this case.
373 * \param visionMeasurementStdDevs Standard deviations of the vision pose
374 * measurement (x position in meters, y position in meters, and heading in
375 * radians). Increase these numbers to trust the vision pose measurement
376 * less.
377 */
378 void AddVisionMeasurement(Pose2d const &visionRobotPose, units::second_t timestamp,
379 std::array<double, 3> const &visionMeasurementStdDevs)
380 {
381 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
382 AddVisionMeasurement(visionRobotPose, timestamp);
383 }
384
385 /**
386 * \brief Updates the pose estimator with wheel encoder and gyro information.
387 * This should be called every loop.
388 *
389 * \param gyroAngle The current gyro angle.
390 * \param wheelPositions The distances traveled by the encoders.
391 *
392 * \returns The estimated pose of the robot in meters.
393 */
394 Pose2d Update(Rotation2d const &gyroAngle, WheelPositions const &wheelPositions)
395 {
396 return UpdateWithTime(utils::GetCurrentTime(), gyroAngle, wheelPositions);
397 }
398
399 /**
400 * \brief Updates the pose estimator with wheel encoder and gyro information. This
401 * should be called every loop.
402 *
403 * \param currentTime The time at which this method was called.
404 * \param gyroAngle The current gyro angle.
405 * \param wheelPositions The distances traveled by the encoders.
406 *
407 * \returns The estimated pose of the robot in meters.
408 */
409 Pose2d UpdateWithTime(units::second_t currentTime, Rotation2d const &gyroAngle, WheelPositions const &wheelPositions)
410 {
411 auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions);
412
413 m_odometryPoseBuffer.AddSample(currentTime, odometryEstimate);
414
415 if (m_visionUpdates.empty()) {
416 m_poseEstimate = std::move(odometryEstimate);
417 } else {
418 auto const visionUpdate = m_visionUpdates.rbegin()->second;
419 m_poseEstimate = visionUpdate.Compensate(odometryEstimate);
420 }
421
422 return GetEstimatedPosition();
423 }
424};
425
426}
427}
428}
429}
The TimeInterpolatableBuffer provides an easy way to estimate past measurements.
Definition TimeInterpolatableBuffer.hpp:31
Class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states ...
Definition SwerveDriveKinematics.hpp:42
Class for swerve drive odometry.
Definition SwerveDrivePoseEstimator.hpp:29
Pose2d const & Pose() const
Returns the position of the robot on the field.
Definition SwerveDrivePoseEstimator.hpp:116
void ResetPosition(Rotation2d const &gyroAngle, WheelPositions wheelPositions, Pose2d const &pose)
Resets the robot's position on the field.
Definition SwerveDrivePoseEstimator.hpp:69
std::vector< SwerveModulePosition > WheelPositions
Definition SwerveDrivePoseEstimator.hpp:32
void ResetRotation(Rotation2d const &rotation)
Resets the rotation of the pose.
Definition SwerveDrivePoseEstimator.hpp:104
Pose2d const & Update(Rotation2d const &gyroAngle, WheelPositions wheelPositions)
Updates the robot's position on the field using forward kinematics and integration of the pose over t...
std::vector< SwerveModuleState > WheelSpeeds
Definition SwerveDrivePoseEstimator.hpp:31
void ResetTranslation(Translation2d const &translation)
Resets the translation of the pose.
Definition SwerveDrivePoseEstimator.hpp:94
SwerveDriveOdometry(SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle, WheelPositions modulePositions, Pose2d initialPose=Pose2d{})
Constructs a SwerveDriveOdometry object.
Definition SwerveDrivePoseEstimator.hpp:51
void ResetPose(Pose2d const &pose)
Resets the pose.
Definition SwerveDrivePoseEstimator.hpp:82
This class wraps Swerve Drive Odometry to fuse latency-compensated vision measurements with swerve dr...
Definition SwerveDrivePoseEstimator.hpp:142
Pose2d UpdateWithTime(units::second_t currentTime, Rotation2d const &gyroAngle, WheelPositions const &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition SwerveDrivePoseEstimator.hpp:409
std::vector< SwerveModulePosition > WheelPositions
Definition SwerveDrivePoseEstimator.hpp:145
void ResetPosition(Rotation2d const &gyroAngle, WheelPositions wheelPositions, Pose2d const &pose)
Resets the robot's position on the field.
Definition SwerveDrivePoseEstimator.hpp:262
void AddVisionMeasurement(Pose2d const &visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
SwerveDrivePoseEstimator(SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle, WheelPositions modulePositions, Pose2d initialPose, std::array< double, 3 > const &stateStdDevs, std::array< double, 3 > const &visionMeasurementStdDevs)
Constructs a SwerveDrivePoseEstimator.
Pose2d GetEstimatedPosition() const
Gets the estimated robot pose.
Definition SwerveDrivePoseEstimator.hpp:314
void ResetTranslation(Translation2d const &translation)
Resets the robot's translation.
Definition SwerveDrivePoseEstimator.hpp:288
std::vector< SwerveModuleState > WheelSpeeds
Definition SwerveDrivePoseEstimator.hpp:144
void ResetPose(Pose2d const &pose)
Resets the robot's pose.
Definition SwerveDrivePoseEstimator.hpp:275
SwerveDrivePoseEstimator(SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle, WheelPositions modulePositions, Pose2d initialPose)
Constructs a SwerveDrivePoseEstimator with default standard deviations for the model and vision measu...
Definition SwerveDrivePoseEstimator.hpp:211
std::optional< Pose2d > SampleAt(units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
void ResetRotation(Rotation2d const &rotation)
Resets the robot's rotation.
Definition SwerveDrivePoseEstimator.hpp:301
void SetVisionMeasurementStdDevs(std::array< double, 3 > const &visionMeasurementStdDevs)
Sets the pose estimator's trust in vision measurements.
Pose2d Update(Rotation2d const &gyroAngle, WheelPositions const &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition SwerveDrivePoseEstimator.hpp:394
void AddVisionMeasurement(Pose2d const &visionRobotPose, units::second_t timestamp, std::array< double, 3 > const &visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivePoseEstimator.hpp:378
units::second_t GetCurrentTime()
Get the current timestamp.
Definition Utils.hpp:29
Definition StatusCodes.h:18
Definition span.hpp:401