CTRE Phoenix 6 C++ 25.3.0
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 std::array<double, 3> m_r{};
175
176 struct VisionMatrices;
177 std::unique_ptr<VisionMatrices> m_matrices;
178
179 /* Maps timestamps to odometry-only pose estimates */
180 TimeInterpolatableBuffer<Pose2d> m_odometryPoseBuffer{kBufferDuration};
181 /*
182 * Maps timestamps to vision updates
183 * Always contains one entry before the oldest entry in m_odometryPoseBuffer,
184 * unless there have been no vision measurements after the last reset
185 */
186 std::map<units::second_t, VisionUpdate> m_visionUpdates;
187
188 Pose2d m_poseEstimate;
189
190 /**
191 * \brief Removes stale vision updates that won't affect sampling.
192 */
193 void CleanUpVisionUpdates();
194
195 /**
196 * \brief Updates the vision matrices to account for changes in standard deviations.
197 */
198 void UpdateVisionMatrices();
199
200public:
201 /**
202 * \brief Constructs a SwerveDrivePoseEstimator with default standard deviations
203 * for the model and vision measurements.
204 *
205 * The default standard deviations of the model states are
206 * 0.1 meters for x, 0.1 meters for y, and 0.1 radians for heading.
207 * The default standard deviations of the vision measurements are
208 * 0.9 meters for x, 0.9 meters for y, and 0.9 radians for heading.
209 *
210 * \param kinematics A correctly-configured kinematics object for your
211 * drivetrain.
212 * \param gyroAngle The current gyro angle.
213 * \param modulePositions The current distance and rotation measurements of
214 * the swerve modules.
215 * \param initialPose The starting pose estimate.
216 */
217 SwerveDrivePoseEstimator(SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle,
218 WheelPositions modulePositions, Pose2d initialPose) :
219 SwerveDrivePoseEstimator{kinematics, gyroAngle, std::move(modulePositions), std::move(initialPose),
220 {0.1, 0.1, 0.1}, {0.9, 0.9, 0.9}}
221 {}
222
223 /**
224 * \brief Constructs a SwerveDrivePoseEstimator.
225 *
226 * \param kinematics A correctly-configured kinematics object for your
227 * drivetrain.
228 * \param gyroAngle The current gyro angle.
229 * \param modulePositions The current distance and rotation measurements of
230 * the swerve modules.
231 * \param initialPose The starting pose estimate.
232 * \param stateStdDevs Standard deviations of the pose estimate (x position in
233 * meters, y position in meters, and heading in radians). Increase these
234 * numbers to trust your state estimate less.
235 * \param visionMeasurementStdDevs Standard deviations of the vision pose
236 * measurement (x position in meters, y position in meters, and heading in
237 * radians). Increase these numbers to trust the vision pose measurement
238 * less.
239 */
240 SwerveDrivePoseEstimator(SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle,
241 WheelPositions modulePositions, Pose2d initialPose,
242 std::array<double, 3> const &stateStdDevs, std::array<double, 3> const &visionMeasurementStdDevs);
243
245
246 /**
247 * \brief Sets the pose estimator's trust in robot odometry. This might be used
248 * to change trust in odometry after an impact with the wall or traversing a bump.
249 *
250 * \param stateStdDevs Standard deviations of the pose estimate (x position in
251 * meters, y position in meters, and heading in radians). Increase these
252 * numbers to trust your state estimate less.
253 */
254 void SetStateStdDevs(std::array<double, 3> const &stateStdDevs)
255 {
256 for (size_t i = 0; i < m_q.size(); ++i) {
257 m_q[i] = stateStdDevs[i] * stateStdDevs[i];
258 }
259 UpdateVisionMatrices();
260 }
261
262 /**
263 * \brief Sets the pose estimator's trust in vision measurements. This might be used
264 * to change trust in vision measurements after the autonomous period, or to
265 * change trust as distance to a vision target increases.
266 *
267 * \param visionMeasurementStdDevs Standard deviations of the vision pose
268 * measurement (x position in meters, y position in meters, and heading in
269 * radians). Increase these numbers to trust the vision pose measurement
270 * less.
271 */
272 void SetVisionMeasurementStdDevs(std::array<double, 3> const &visionMeasurementStdDevs)
273 {
274 for (size_t i = 0; i < m_r.size(); ++i) {
275 m_r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i];
276 }
277 UpdateVisionMatrices();
278 }
279
280 /**
281 * \brief Resets the robot's position on the field.
282 *
283 * The gyroscope angle does not need to be reset in the user's robot code.
284 * The library automatically takes care of offsetting the gyro angle.
285 *
286 * \param gyroAngle The current gyro angle.
287 * \param wheelPositions The distances traveled by the encoders.
288 * \param pose The estimated pose of the robot on the field.
289 */
290 void ResetPosition(Rotation2d const &gyroAngle, WheelPositions wheelPositions, Pose2d const &pose)
291 {
292 m_odometry.ResetPosition(gyroAngle, std::move(wheelPositions), pose);
293 m_odometryPoseBuffer.Clear();
294 m_visionUpdates.clear();
295 m_poseEstimate = m_odometry.Pose();
296 }
297
298 /**
299 * \brief Resets the robot's pose.
300 *
301 * \param pose The pose to reset to.
302 */
303 void ResetPose(Pose2d const &pose)
304 {
305 m_odometry.ResetPose(pose);
306 m_odometryPoseBuffer.Clear();
307 m_visionUpdates.clear();
308 m_poseEstimate = m_odometry.Pose();
309 }
310
311 /**
312 * \brief Resets the robot's translation.
313 *
314 * \param translation The pose to translation to.
315 */
316 void ResetTranslation(Translation2d const &translation)
317 {
318 m_odometry.ResetTranslation(translation);
319 m_odometryPoseBuffer.Clear();
320 m_visionUpdates.clear();
321 m_poseEstimate = m_odometry.Pose();
322 }
323
324 /**
325 * \brief Resets the robot's rotation.
326 *
327 * \param rotation The rotation to reset to.
328 */
329 void ResetRotation(Rotation2d const &rotation)
330 {
331 m_odometry.ResetRotation(rotation);
332 m_odometryPoseBuffer.Clear();
333 m_visionUpdates.clear();
334 m_poseEstimate = m_odometry.Pose();
335 }
336
337 /**
338 * \brief Gets the estimated robot pose.
339 *
340 * \returns The estimated robot pose in meters.
341 */
342 Pose2d GetEstimatedPosition() const
343 {
344 return m_poseEstimate;
345 }
346
347 /**
348 * \brief Return the pose at a given timestamp, if the buffer is not empty.
349 *
350 * \param timestamp The pose's timestamp.
351 * \returns The pose at the given timestamp (or std::nullopt if the buffer is
352 * empty).
353 */
354 std::optional<Pose2d> SampleAt(units::second_t timestamp) const;
355
356 /**
357 * \brief Adds a vision measurement to the Kalman Filter. This will correct
358 * the odometry pose estimate while still accounting for measurement noise.
359 *
360 * This method can be called as infrequently as you want, as long as you are
361 * calling Update() every loop.
362 *
363 * To promote stability of the pose estimate and make it robust to bad vision
364 * data, we recommend only adding vision measurements that are already within
365 * one meter or so of the current pose estimate.
366 *
367 * \param visionRobotPose The pose of the robot as measured by the vision
368 * camera.
369 * \param timestamp The timestamp of the vision measurement in seconds. Note
370 * that if you don't use your own time source by calling UpdateWithTime(),
371 * then you must use a timestamp with an epoch since system startup (i.e.,
372 * the epoch of this timestamp is the same epoch as utils#GetCurrentTime().
373 * This means that you should use utils#GetCurrentTime() as your time source
374 * in this case.
375 */
376 void AddVisionMeasurement(Pose2d const &visionRobotPose, units::second_t timestamp);
377
378 /**
379 * \brief Adds a vision measurement to the Kalman Filter. This will correct
380 * the odometry pose estimate while still accounting for measurement noise.
381 *
382 * This method can be called as infrequently as you want, as long as you are
383 * calling Update() every loop.
384 *
385 * To promote stability of the pose estimate and make it robust to bad vision
386 * data, we recommend only adding vision measurements that are already within
387 * one meter or so of the current pose estimate.
388 *
389 * Note that the vision measurement standard deviations passed into this
390 * method will continue to apply to future measurements until a subsequent
391 * call to SetVisionMeasurementStdDevs() or this method.
392 *
393 * \param visionRobotPose The pose of the robot as measured by the vision
394 * camera.
395 * \param timestamp The timestamp of the vision measurement in seconds. Note
396 * that if you don't use your own time source by calling UpdateWithTime(),
397 * then you must use a timestamp with an epoch since system startup (i.e.,
398 * the epoch of this timestamp is the same epoch as utils#GetCurrentTime().
399 * This means that you should use utils#GetCurrentTime() as your time source
400 * in this case.
401 * \param visionMeasurementStdDevs Standard deviations of the vision pose
402 * measurement (x position in meters, y position in meters, and heading in
403 * radians). Increase these numbers to trust the vision pose measurement
404 * less.
405 */
406 void AddVisionMeasurement(Pose2d const &visionRobotPose, units::second_t timestamp,
407 std::array<double, 3> const &visionMeasurementStdDevs)
408 {
409 SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
410 AddVisionMeasurement(visionRobotPose, timestamp);
411 }
412
413 /**
414 * \brief Updates the pose estimator with wheel encoder and gyro information.
415 * This should be called every loop.
416 *
417 * \param gyroAngle The current gyro angle.
418 * \param wheelPositions The distances traveled by the encoders.
419 *
420 * \returns The estimated pose of the robot in meters.
421 */
422 Pose2d Update(Rotation2d const &gyroAngle, WheelPositions const &wheelPositions)
423 {
424 return UpdateWithTime(utils::GetCurrentTime(), gyroAngle, wheelPositions);
425 }
426
427 /**
428 * \brief Updates the pose estimator with wheel encoder and gyro information. This
429 * should be called every loop.
430 *
431 * \param currentTime The time at which this method was called.
432 * \param gyroAngle The current gyro angle.
433 * \param wheelPositions The distances traveled by the encoders.
434 *
435 * \returns The estimated pose of the robot in meters.
436 */
437 Pose2d UpdateWithTime(units::second_t currentTime, Rotation2d const &gyroAngle, WheelPositions const &wheelPositions)
438 {
439 auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions);
440
441 m_odometryPoseBuffer.AddSample(currentTime, odometryEstimate);
442
443 if (m_visionUpdates.empty()) {
444 m_poseEstimate = std::move(odometryEstimate);
445 } else {
446 auto const visionUpdate = m_visionUpdates.rbegin()->second;
447 m_poseEstimate = visionUpdate.Compensate(odometryEstimate);
448 }
449
450 return GetEstimatedPosition();
451 }
452};
453
454}
455}
456}
457}
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:437
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:290
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:342
void ResetTranslation(Translation2d const &translation)
Resets the robot's translation.
Definition SwerveDrivePoseEstimator.hpp:316
std::vector< SwerveModuleState > WheelSpeeds
Definition SwerveDrivePoseEstimator.hpp:144
void ResetPose(Pose2d const &pose)
Resets the robot's pose.
Definition SwerveDrivePoseEstimator.hpp:303
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:217
std::optional< Pose2d > SampleAt(units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
void SetStateStdDevs(std::array< double, 3 > const &stateStdDevs)
Sets the pose estimator's trust in robot odometry.
Definition SwerveDrivePoseEstimator.hpp:254
void ResetRotation(Rotation2d const &rotation)
Resets the robot's rotation.
Definition SwerveDrivePoseEstimator.hpp:329
void SetVisionMeasurementStdDevs(std::array< double, 3 > const &visionMeasurementStdDevs)
Sets the pose estimator's trust in vision measurements.
Definition SwerveDrivePoseEstimator.hpp:272
Pose2d Update(Rotation2d const &gyroAngle, WheelPositions const &wheelPositions)
Updates the pose estimator with wheel encoder and gyro information.
Definition SwerveDrivePoseEstimator.hpp:422
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:406
units::second_t GetCurrentTime()
Get the current timestamp.
Definition Utils.hpp:29
Definition MotionMagicExpoTorqueCurrentFOC.hpp:18
Definition span.hpp:401