CTRE Phoenix 6 C++ 25.0.0-beta-4
Loading...
Searching...
No Matches
SwerveDrivetrainImpl.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
14
15#include <atomic>
16#include <thread>
17
18namespace ctre {
19namespace phoenix6 {
20namespace swerve {
21namespace impl {
22
23/**
24 * \brief Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
25 *
26 * This class handles the kinematics and odometry (but not configuration)
27 * of a swerve drive utilizing CTR Electronics devices. Users should
28 * create a high-level SwerveDrivetrain instead of using this directly.
29 */
31public:
32 /** \brief Performs swerve module updates in a separate thread to minimize latency. */
34 protected:
35 static constexpr int START_THREAD_PRIORITY = 1; // Testing shows 1 (minimum realtime) is sufficient for tighter
36 // odometry loops.
37 // If the odometry period is far away from the desired frequency,
38 // increasing this may help
39
41
42 std::thread _thread;
43 std::mutex _threadMtx;
44 std::atomic<bool> _isRunning = false;
45
46 std::vector<BaseStatusSignal *> _allSignals;
47
48 static constexpr int kLowPassTaps = 50;
50 bool _lastTimeValid = false;
51 units::second_t _lastTime{};
52 units::second_t _averageLoopTime{};
53
54 std::atomic<int32_t> _successfulDaqs{};
55 std::atomic<int32_t> _failedDaqs{};
56
59
60 public:
63 {
64 Stop();
65 }
66
67 /**
68 * \brief Starts the odometry thread.
69 */
70 void Start()
71 {
72 std::lock_guard<std::mutex> lock{_threadMtx};
73 if (!_thread.joinable()) {
74 _isRunning.store(true, std::memory_order_relaxed);
75 _thread = std::thread{[this] { Run(); }};
76 }
77 }
78
79 /**
80 * \brief Stops the odometry thread.
81 */
82 void Stop()
83 {
84 std::lock_guard<std::mutex> lock{_threadMtx};
85 if (_thread.joinable()) {
86 _isRunning.store(false, std::memory_order_relaxed);
87 _thread.join();
88 }
89 }
90
91 /**
92 * \brief Check if the odometry is currently valid.
93 *
94 * \returns True if odometry is valid
95 */
96 bool IsOdometryValid() const
97 {
98 return _successfulDaqs.load(std::memory_order_relaxed) > 2;
99 }
100
101 /**
102 * \brief Sets the odometry thread priority to a real time priority under the specified priority level
103 *
104 * \param priority Priority level to set the odometry thread to.
105 * This is a value between 0 and 99, with 99 indicating higher priority and 0 indicating lower priority.
106 */
107 void SetThreadPriority(int priority)
108 {
109 _threadPriorityToSet.store(priority, std::memory_order_relaxed);
110 }
111
112 protected:
113 void Run();
114 };
115
116 /**
117 * \brief Plain-Old-Data class holding the state of the swerve drivetrain.
118 * This encapsulates most data that is relevant for telemetry or
119 * decision-making from the Swerve Drive.
120 */
122 /** \brief The current pose of the robot */
123 Pose2d Pose;
124 /** \brief The current velocity of the robot */
125 ChassisSpeeds Speeds;
126 /** \brief The current module states */
127 std::vector<SwerveModuleState> ModuleStates;
128 /** \brief The target module states */
129 std::vector<SwerveModuleState> ModuleTargets;
130 /** \brief The current module positions */
131 std::vector<SwerveModulePosition> ModulePositions;
132 /** \brief The raw heading of the robot, unaffected by vision updates and odometry resets */
133 Rotation2d RawHeading;
134 /** \brief The timestamp of the state capture, in the timebase of utils#GetCurrentTime() */
135 units::second_t Timestamp;
136 /** \brief The measured odometry update period */
137 units::second_t OdometryPeriod;
138 /** \brief Number of successful data acquisitions */
140 /** \brief Number of failed data acquisitions */
141 int32_t FailedDaqs;
142 };
143
144 /**
145 * \brief Contains everything the control requests need to calculate the module state.
146 */
148 /** \brief The kinematics object used for control */
150 /** \brief The locations of the swerve modules */
151 Translation2d const *moduleLocations;
152 /** \brief The max speed of the robot at 12 V output */
153 units::meters_per_second_t kMaxSpeed;
154
155 /** \brief The forward direction from the operator perspective */
157 /** \brief The current chassis speeds of the robot */
158 ChassisSpeeds currentChassisSpeed;
159 /** \brief The current pose of the robot */
161 /** \brief The timestamp of the current control apply, in the timebase of utils#GetCurrentTime() */
162 units::second_t timestamp;
163 /** \brief The update period of control apply */
164 units::second_t updatePeriod;
165 };
166
167 using SwerveRequestFunc = std::function<ctre::phoenix::StatusCode(ControlParameters const &, std::vector<std::unique_ptr<SwerveModuleImpl>> const &)>;
168
169private:
170 friend class OdometryThread;
171
172 CANBus _canbus;
173
176 StatusSignal<units::degrees_per_second_t> _pigeonAngularVelocity;
177
178 std::vector<std::unique_ptr<SwerveModuleImpl>> _modules;
179
180 std::vector<Translation2d> _moduleLocations;
181 std::vector<SwerveModulePosition> _modulePositions;
182 std::vector<SwerveModuleState> _moduleStates;
183
184 SwerveDriveKinematics _kinematics;
185 SwerveDrivePoseEstimator _odometry;
186
187 Rotation2d _operatorForwardDirection{};
188
189 SwerveRequestFunc _requestToApply = [](auto&, auto&) { return ctre::phoenix::StatusCode::OK; };
190 ControlParameters _requestParameters{};
191
192 mutable std::recursive_mutex _stateLock;
193 SwerveDriveState _cachedState{};
194 std::function<void(SwerveDriveState const &)> _telemetryFunction{};
195
196 bool _isOnCANFD;
197 units::hertz_t _updateFrequency;
198
199 std::unique_ptr<OdometryThread> _odometryThread;
200
201public:
202 /**
203 * \brief Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
204 *
205 * This constructs the underlying hardware devices, which can be accessed through
206 * getters in the classes.
207 *
208 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
209 * \param modules Constants for each specific module
210 */
211 template < typename... ModuleConstants,
212 typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> > >
213 SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules) :
214 SwerveDrivetrainImpl{drivetrainConstants, std::array{modules...}}
215 {}
216 /**
217 * \brief Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
218 *
219 * This constructs the underlying hardware devices, which can be accessed through
220 * getters in the classes.
221 *
222 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
223 * \param modules Constants for each specific module
224 */
226 SwerveDrivetrainImpl{drivetrainConstants, 0_Hz, modules}
227 {}
228
229 /**
230 * \brief Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
231 *
232 * This constructs the underlying hardware devices, which can be accessed through
233 * getters in the classes.
234 *
235 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
236 * \param odometryUpdateFrequency The frequency to run the odometry loop. If
237 * unspecified or set to 0 Hz, this is 250 Hz on
238 * CAN FD, and 100 Hz on CAN 2.0.
239 * \param modules Constants for each specific module
240 */
241 template < typename... ModuleConstants,
242 typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> > >
243 SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency,
244 ModuleConstants const &... modules) :
245 SwerveDrivetrainImpl{drivetrainConstants, odometryUpdateFrequency, std::array{modules...}}
246 {}
247 /**
248 * \brief Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
249 *
250 * This constructs the underlying hardware devices, which can be accessed through
251 * getters in the classes.
252 *
253 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
254 * \param odometryUpdateFrequency The frequency to run the odometry loop. If
255 * unspecified or set to 0 Hz, this is 250 Hz on
256 * CAN FD, and 100 Hz on CAN 2.0.
257 * \param modules Constants for each specific module
258 */
259 SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency,
261 SwerveDrivetrainImpl{drivetrainConstants, odometryUpdateFrequency, std::array{0.1, 0.1, 0.1}, std::array{0.9, 0.9, 0.9}, modules}
262 {}
263
264 /**
265 * \brief Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
266 *
267 * This constructs the underlying hardware devices, which can be accessed through
268 * getters in the classes.
269 *
270 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
271 * \param odometryUpdateFrequency The frequency to run the odometry loop. If
272 * unspecified or set to 0 Hz, this is 250 Hz on
273 * CAN FD, and 100 Hz on CAN 2.0.
274 * \param odometryStandardDeviation The standard deviation for odometry calculation
275 * in the form [x, y, theta]ᵀ, with units in meters
276 * and radians
277 * \param visionStandardDeviation The standard deviation for vision calculation
278 * in the form [x, y, theta]ᵀ, with units in meters
279 * and radians
280 * \param modules Constants for each specific module
281 */
282 template < typename... ModuleConstants,
283 typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> > >
284 SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency,
285 std::array<double, 3> const &odometryStandardDeviation, std::array<double, 3> const &visionStandardDeviation,
286 ModuleConstants const &... modules) :
287 SwerveDrivetrainImpl{drivetrainConstants, odometryUpdateFrequency, odometryStandardDeviation,
288 visionStandardDeviation, std::array{modules...}}
289 {}
290 /**
291 * \brief Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
292 *
293 * This constructs the underlying hardware devices, which can be accessed through
294 * getters in the classes.
295 *
296 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
297 * \param odometryUpdateFrequency The frequency to run the odometry loop. If
298 * unspecified or set to 0 Hz, this is 250 Hz on
299 * CAN FD, and 100 Hz on CAN 2.0.
300 * \param odometryStandardDeviation The standard deviation for odometry calculation
301 * in the form [x, y, theta]ᵀ, with units in meters
302 * and radians
303 * \param visionStandardDeviation The standard deviation for vision calculation
304 * in the form [x, y, theta]ᵀ, with units in meters
305 * and radians
306 * \param modules Constants for each specific module
307 */
308 SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency,
309 std::array<double, 3> const &odometryStandardDeviation, std::array<double, 3> const &visionStandardDeviation,
311
312 /**
313 * \brief Gets whether the drivetrain is on a CAN FD bus.
314 *
315 * \returns true if on CAN FD
316 */
317 bool IsOnCANFD() const { return _isOnCANFD; }
318
319 /**
320 * \brief Gets the target odometry update frequency.
321 *
322 * \returns Target odometry update frequency
323 */
324 units::hertz_t GetOdometryFrequency() const { return _updateFrequency; }
325
326 /**
327 * \brief Gets a reference to the odometry thread.
328 *
329 * \returns Odometry thread
330 */
331 OdometryThread &GetOdometryThread() { return *_odometryThread; }
332
333 /**
334 * \brief Check if the odometry is currently valid.
335 *
336 * \returns True if odometry is valid
337 */
338 bool IsOdometryValid() const
339 {
340 return _odometryThread->IsOdometryValid();
341 }
342
343 /**
344 * \brief Gets a reference to the kinematics used for the drivetrain.
345 *
346 * \returns Swerve kinematics
347 */
348 SwerveDriveKinematics const &GetKinematics() const { return _kinematics; }
349
350 /**
351 * \brief Applies the specified control function to this swerve drivetrain.
352 *
353 * \param request Request function to apply
354 */
356 {
357 std::lock_guard<std::recursive_mutex> lock{_stateLock};
358 if (request) {
359 _requestToApply = std::move(request);
360 } else {
361 _requestToApply = [](auto&, auto&) { return ctre::phoenix::StatusCode::OK; };
362 }
363 }
364
365 /**
366 * \brief Immediately runs the provided temporary control function.
367 *
368 * This is used to accelerate non-native swerve requests and
369 * can only be called from the odometry thread. Otherwise,
370 * SetControl should be used instead.
371 *
372 * \param request Request function to invoke
373 */
375 {
376 std::lock_guard<std::recursive_mutex> lock{_stateLock};
377 return request(_requestParameters, _modules);
378 }
379
380 /**
381 * \brief Gets the current state of the swerve drivetrain.
382 * This includes information such as the pose estimate,
383 * module states, and chassis speeds.
384 *
385 * \returns Current state of the drivetrain
386 */
388 {
389 std::lock_guard<std::recursive_mutex> lock{_stateLock};
390 return _cachedState;
391 }
392
393 /**
394 * \brief Register the specified lambda to be executed whenever the SwerveDriveState
395 * is updated in the odometry thread.
396 *
397 * It is imperative that this function is cheap, as it will be executed synchronously
398 * with the odometry call; if this takes a long time, it may negatively impact the
399 * odometry of this stack.
400 *
401 * This can also be used for logging data if the function performs logging instead of telemetry.
402 * Additionally, the SwerveDriveState object can be cloned and stored for later processing.
403 *
404 * \param telemetryFunction Function to call for telemetry or logging
405 */
406 void RegisterTelemetry(std::function<void(SwerveDriveState const &)> telemetryFunction)
407 {
408 std::lock_guard<std::recursive_mutex> lock{_stateLock};
409 _telemetryFunction = std::move(telemetryFunction);
410 }
411
412 /**
413 * \brief Configures the neutral mode to use for all modules' drive motors.
414 *
415 * \param neutralMode The drive motor neutral mode
416 * \returns Status code of the first failed config call, or OK if all succeeded
417 */
419 {
421 for (auto &module : _modules) {
422 auto status = module->ConfigNeutralMode(neutralMode);
423 if (retval.IsOK()) {
424 retval = status;
425 }
426 }
427 return retval;
428 }
429
430 /**
431 * \brief Zero's this swerve drive's odometry entirely.
432 *
433 * This will zero the entire odometry, and place the robot at 0,0
434 */
436 {
437 std::lock_guard<std::recursive_mutex> lock{_stateLock};
438
439 for (size_t i = 0; i < _modules.size(); ++i) {
440 _modules[i]->ResetPosition();
441 _modulePositions[i] = _modules[i]->GetPosition(true);
442 }
443 _odometry.ResetPosition({_pigeonYaw.GetValue()}, _modulePositions, Pose2d{});
444 /* We need to update our cached pose immediately to prevent race conditions */
445 _cachedState.Pose = _odometry.GetEstimatedPosition();
446 }
447
448 /**
449 * \brief Resets the rotation of the robot pose to 0 from the
450 * requests#ForwardPerspectiveValue#OperatorPerspective perspective.
451 * This makes the current orientation of the robot X forward for
452 * field-centric maneuvers.
453 *
454 * This is equivalent to calling ResetRotation with the operator
455 * perspective rotation.
456 */
458 {
459 ResetRotation(_operatorForwardDirection);
460 }
461
462 /**
463 * \brief Resets the pose of the robot. The pose should be from the
464 * requests#ForwardPerspectiveValue#BlueAlliance perspective.
465 *
466 * \param pose Pose to make the current pose
467 */
468 void ResetPose(Pose2d const &pose)
469 {
470 std::lock_guard<std::recursive_mutex> lock{_stateLock};
471
472 _odometry.ResetPose(pose);
473 /* We need to update our cached pose immediately to prevent race conditions */
474 _cachedState.Pose = _odometry.GetEstimatedPosition();
475 }
476
477 /**
478 * \brief Resets the translation of the robot pose without affecting rotation.
479 * The translation should be from the requests#ForwardPerspectiveValue#BlueAlliance
480 * perspective.
481 *
482 * \param translation Translation to make the current translation
483 */
484 void ResetTranslation(Translation2d const &translation)
485 {
486 std::lock_guard<std::recursive_mutex> lock{_stateLock};
487
488 _odometry.ResetTranslation(translation);
489 /* We need to update our cached pose immediately to prevent race conditions */
490 _cachedState.Pose = _odometry.GetEstimatedPosition();
491 }
492
493 /**
494 * \brief Resets the rotation of the robot pose without affecting translation.
495 * The rotation should be from the requests#ForwardPerspectiveValue#BlueAlliance
496 * perspective.
497 *
498 * \param rotation Rotation to make the current rotation
499 */
500 void ResetRotation(Rotation2d const &rotation)
501 {
502 std::lock_guard<std::recursive_mutex> lock{_stateLock};
503
504 _odometry.ResetRotation(rotation);
505 /* We need to update our cached pose immediately to prevent race conditions */
506 _cachedState.Pose = _odometry.GetEstimatedPosition();
507 }
508
509 /**
510 * \brief Takes the requests#ForwardPerspectiveValue#BlueAlliance perpective
511 * direction and treats it as the forward direction for
512 * requests#ForwardPerspectiveValue#OperatorPerspective.
513 *
514 * If the operator is in the Blue Alliance Station, this should be 0 degrees.
515 * If the operator is in the Red Alliance Station, this should be 180 degrees.
516 *
517 * This does not change the robot pose, which is in the
518 * requests#ForwardPerspectiveValue#BlueAlliance perspective.
519 * As a result, the robot pose may need to be reset using ResetPose.
520 *
521 * \param fieldDirection Heading indicating which direction is forward from
522 * the requests#ForwardPerspectiveValue#BlueAlliance perspective
523 */
524 void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
525 {
526 std::lock_guard<std::recursive_mutex> lock{_stateLock};
527 _operatorForwardDirection = fieldDirection;
528 }
529
530 /**
531 * \brief Returns the requests#ForwardPerspectiveValue#BlueAlliance perpective
532 * direction that is treated as the forward direction for
533 * requests#ForwardPerspectiveValue#OperatorPerspective.
534 *
535 * If the operator is in the Blue Alliance Station, this should be 0 degrees.
536 * If the operator is in the Red Alliance Station, this should be 180 degrees.
537 *
538 * \returns Heading indicating which direction is forward from
539 * the requests#ForwardPerspectiveValue#BlueAlliance perspective
540 */
542 {
543 std::lock_guard<std::recursive_mutex> lock{_stateLock};
544 return _operatorForwardDirection;
545 }
546
547 /**
548 * \brief Adds a vision measurement to the Kalman Filter. This will correct the
549 * odometry pose estimate while still accounting for measurement noise.
550 *
551 * This method can be called as infrequently as you want, as long as you are
552 * calling impl#SwerveDrivePoseEstimator#Update every loop.
553 *
554 * To promote stability of the pose estimate and make it robust to bad vision
555 * data, we recommend only adding vision measurements that are already within
556 * one meter or so of the current pose estimate.
557 *
558 * \param visionRobotPose The pose of the robot as measured by the
559 * vision camera.
560 * \param timestamp The timestamp of the vision measurement in
561 * seconds. Note that if you don't use your
562 * own time source by calling
563 * impl#SwerveDrivePoseEstimator#UpdateWithTime,
564 * then you must use a timestamp with an epoch
565 * since system startup (i.e., the epoch of this
566 * timestamp is the same epoch as utils#GetCurrentTime).
567 * This means that you should use utils#GetCurrentTime
568 * as your time source in this case.
569 */
570 void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp)
571 {
572 std::lock_guard<std::recursive_mutex> lock{_stateLock};
573 _odometry.AddVisionMeasurement(visionRobotPose, timestamp);
574 }
575
576 /**
577 * \brief Adds a vision measurement to the Kalman Filter. This will correct the
578 * odometry pose estimate while still accounting for measurement noise.
579 *
580 * This method can be called as infrequently as you want, as long as you are
581 * calling impl#SwerveDrivePoseEstimator#Update every loop.
582 *
583 * To promote stability of the pose estimate and make it robust to bad vision
584 * data, we recommend only adding vision measurements that are already within
585 * one meter or so of the current pose estimate.
586 *
587 * Note that the vision measurement standard deviations passed into this method
588 * will continue to apply to future measurements until a subsequent call to
589 * #SetVisionMeasurementStdDevs or this method.
590 *
591 * \param visionRobotPose The pose of the robot as measured by the
592 * vision camera.
593 * \param timestamp The timestamp of the vision measurement in
594 * seconds. Note that if you don't use your
595 * own time source by calling
596 * impl#SwerveDrivePoseEstimator#UpdateWithTime,
597 * then you must use a timestamp with an epoch
598 * since system startup (i.e., the epoch of this
599 * timestamp is the same epoch as utils#GetCurrentTime).
600 * This means that you should use utils#GetCurrentTime
601 * as your time source in this case.
602 * \param visionMeasurementStdDevs Standard deviations of the vision pose
603 * measurement (x position in meters, y position
604 * in meters, and heading in radians). Increase
605 * these numbers to trust the vision pose
606 * measurement less.
607 */
609 Pose2d visionRobotPose,
610 units::second_t timestamp,
611 std::array<double, 3> visionMeasurementStdDevs)
612 {
613 std::lock_guard<std::recursive_mutex> lock{_stateLock};
614 _odometry.AddVisionMeasurement(visionRobotPose, timestamp, visionMeasurementStdDevs);
615 }
616
617 /**
618 * \brief Sets the pose estimator's trust of global measurements. This might be used to
619 * change trust in vision measurements after the autonomous period, or to change
620 * trust as distance to a vision target increases.
621 *
622 * \param visionMeasurementStdDevs Standard deviations of the vision
623 * measurements. Increase these
624 * numbers to trust global measurements from
625 * vision less. This matrix is in the form [x,
626 * y, theta]ᵀ, with units in meters and radians.
627 */
628 void SetVisionMeasurementStdDevs(std::array<double, 3> visionMeasurementStdDevs)
629 {
630 std::lock_guard<std::recursive_mutex> lock{_stateLock};
631 _odometry.SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
632 }
633
634 /**
635 * \brief Return the pose at a given timestamp, if the buffer is not empty.
636 *
637 * \param timestamp The pose's timestamp. Note that if you don't use your
638 * own time source by calling
639 * impl#SwerveDrivePoseEstimator#UpdateWithTime,
640 * then you must use a timestamp with an epoch
641 * since system startup (i.e., the epoch of this
642 * timestamp is the same epoch as utils#GetCurrentTime).
643 * This means that you should use utils#GetCurrentTime
644 * as your time source in this case.
645 * \returns The pose at the given timestamp (or std::nullopt if the buffer is
646 * empty).
647 */
648 std::optional<Pose2d> SamplePoseAt(units::second_t timestamp)
649 {
650 std::lock_guard<std::recursive_mutex> lock{_stateLock};
651 return _odometry.SampleAt(timestamp);
652 }
653
654 /**
655 * \brief Get a reference to the module at the specified index.
656 * The index corresponds to the module described in the constructor.
657 *
658 * \param index Which module to get
659 * \returns Reference to SwerveModuleImpl
660 */
661 SwerveModuleImpl &GetModule(size_t index) { return *_modules[index]; }
662 /**
663 * \brief Get a reference to the module at the specified index.
664 * The index corresponds to the module described in the constructor.
665 *
666 * \param index Which module to get
667 * \returns Reference to SwerveModuleImpl
668 */
669 SwerveModuleImpl const &GetModule(size_t index) const { return *_modules[index]; }
670 /**
671 * \brief Get a reference to the full array of modules.
672 * The indexes correspond to the module described in the constructor.
673 *
674 * \returns Reference to the SwerveModuleImpl array
675 */
676 std::vector<std::unique_ptr<SwerveModuleImpl>> const &GetModules() const { return _modules; }
677
678 /**
679 * \brief Gets the locations of the swerve modules.
680 *
681 * \returns Reference to the array of swerve module locations
682 */
683 std::vector<Translation2d> const &GetModuleLocations() const { return _moduleLocations; }
684
685 /**
686 * \brief Gets this drivetrain's Pigeon 2 reference.
687 *
688 * This should be used only to access signals and change configurations that the
689 * swerve drivetrain does not configure itself.
690 *
691 * \returns This drivetrain's Pigeon 2 reference
692 */
694};
695
696}
697}
698}
699}
Class for getting information about an available CAN bus.
Definition CANBus.hpp:19
Represents a status signal with data of type T, and operations available to retrieve information abou...
Definition StatusSignal.hpp:657
T GetValue() const
Gets the cached value from this status signal.
Definition StatusSignal.hpp:759
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:1116
The state of the motor controller bridge when output is neutral or disabled.
Definition SpnEnums.hpp:2202
This class implements a linear, digital filter.
Definition LinearFilter.hpp:78
static LinearFilter< T > MovingAverage(int taps)
Creates a K-tap FIR moving average filter of the form: y[n] = 1/k (x[k] + x[k-1] + … + x[0])
Definition LinearFilter.hpp:160
Class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states ...
Definition SwerveDriveKinematics.hpp:42
This class wraps Swerve Drive Odometry to fuse latency-compensated vision measurements with swerve dr...
Definition SwerveDrivePoseEstimator.hpp:142
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.
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
void ResetPose(Pose2d const &pose)
Resets the robot's pose.
Definition SwerveDrivePoseEstimator.hpp:275
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.
Performs swerve module updates in a separate thread to minimize latency.
Definition SwerveDrivetrainImpl.hpp:33
std::thread _thread
Definition SwerveDrivetrainImpl.hpp:42
std::atomic< bool > _isRunning
Definition SwerveDrivetrainImpl.hpp:44
std::vector< BaseStatusSignal * > _allSignals
Definition SwerveDrivetrainImpl.hpp:46
bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrainImpl.hpp:96
units::second_t _lastTime
Definition SwerveDrivetrainImpl.hpp:51
void Stop()
Stops the odometry thread.
Definition SwerveDrivetrainImpl.hpp:82
std::atomic< int > _threadPriorityToSet
Definition SwerveDrivetrainImpl.hpp:57
static constexpr int START_THREAD_PRIORITY
Definition SwerveDrivetrainImpl.hpp:35
LinearFilter< units::second_t > _lowPass
Definition SwerveDrivetrainImpl.hpp:49
std::atomic< int32_t > _failedDaqs
Definition SwerveDrivetrainImpl.hpp:55
void Start()
Starts the odometry thread.
Definition SwerveDrivetrainImpl.hpp:70
bool _lastTimeValid
Definition SwerveDrivetrainImpl.hpp:50
units::second_t _averageLoopTime
Definition SwerveDrivetrainImpl.hpp:52
SwerveDrivetrainImpl * _drivetrain
Definition SwerveDrivetrainImpl.hpp:40
void SetThreadPriority(int priority)
Sets the odometry thread priority to a real time priority under the specified priority level.
Definition SwerveDrivetrainImpl.hpp:107
std::atomic< int32_t > _successfulDaqs
Definition SwerveDrivetrainImpl.hpp:54
std::mutex _threadMtx
Definition SwerveDrivetrainImpl.hpp:43
static constexpr int kLowPassTaps
Definition SwerveDrivetrainImpl.hpp:48
int _lastThreadPriority
Definition SwerveDrivetrainImpl.hpp:58
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrainImpl.hpp:30
void TareEverything()
Zero's this swerve drive's odometry entirely.
Definition SwerveDrivetrainImpl.hpp:435
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, std::array< double, 3 > const &odometryStandardDeviation, std::array< double, 3 > const &visionStandardDeviation, span< SwerveModuleConstants const > modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
std::function< ctre::phoenix::StatusCode(ControlParameters const &, std::vector< std::unique_ptr< SwerveModuleImpl > > const &)> SwerveRequestFunc
Definition SwerveDrivetrainImpl.hpp:167
void SetControl(SwerveRequestFunc &&request)
Applies the specified control function to this swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:355
std::vector< Translation2d > const & GetModuleLocations() const
Gets the locations of the swerve modules.
Definition SwerveDrivetrainImpl.hpp:683
units::hertz_t GetOdometryFrequency() const
Gets the target odometry update frequency.
Definition SwerveDrivetrainImpl.hpp:324
SwerveDriveState GetState() const
Gets the current state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:387
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
Definition SwerveDrivetrainImpl.hpp:213
void SeedFieldCentric()
Resets the rotation of the robot pose to 0 from the requests::ForwardPerspectiveValue::OperatorPerspe...
Definition SwerveDrivetrainImpl.hpp:457
SwerveModuleImpl const & GetModule(size_t index) const
Get a reference to the module at the specified index.
Definition SwerveDrivetrainImpl.hpp:669
bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrainImpl.hpp:338
void ResetRotation(Rotation2d const &rotation)
Resets the rotation of the robot pose without affecting translation.
Definition SwerveDrivetrainImpl.hpp:500
hardware::core::CorePigeon2 & GetPigeon2()
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrainImpl.hpp:693
void RegisterTelemetry(std::function< void(SwerveDriveState const &)> telemetryFunction)
Register the specified lambda to be executed whenever the SwerveDriveState is updated in the odometry...
Definition SwerveDrivetrainImpl.hpp:406
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, std::array< double, 3 > const &odometryStandardDeviation, std::array< double, 3 > const &visionStandardDeviation, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
Definition SwerveDrivetrainImpl.hpp:284
void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp, std::array< double, 3 > visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrainImpl.hpp:608
std::vector< std::unique_ptr< SwerveModuleImpl > > const & GetModules() const
Get a reference to the full array of modules.
Definition SwerveDrivetrainImpl.hpp:676
ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrainImpl.hpp:418
SwerveDriveKinematics const & GetKinematics() const
Gets a reference to the kinematics used for the drivetrain.
Definition SwerveDrivetrainImpl.hpp:348
SwerveModuleImpl & GetModule(size_t index)
Get a reference to the module at the specified index.
Definition SwerveDrivetrainImpl.hpp:661
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, span< SwerveModuleConstants const > modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
Definition SwerveDrivetrainImpl.hpp:225
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, span< SwerveModuleConstants const > modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
Definition SwerveDrivetrainImpl.hpp:259
void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the f...
Definition SwerveDrivetrainImpl.hpp:524
Rotation2d GetOperatorForwardDirection() const
Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as t...
Definition SwerveDrivetrainImpl.hpp:541
OdometryThread & GetOdometryThread()
Gets a reference to the odometry thread.
Definition SwerveDrivetrainImpl.hpp:331
std::optional< Pose2d > SamplePoseAt(units::second_t timestamp)
Return the pose at a given timestamp, if the buffer is not empty.
Definition SwerveDrivetrainImpl.hpp:648
bool IsOnCANFD() const
Gets whether the drivetrain is on a CAN FD bus.
Definition SwerveDrivetrainImpl.hpp:317
void SetVisionMeasurementStdDevs(std::array< double, 3 > visionMeasurementStdDevs)
Sets the pose estimator's trust of global measurements.
Definition SwerveDrivetrainImpl.hpp:628
ctre::phoenix::StatusCode RunTempRequest(SwerveRequestFunc &&request) const
Immediately runs the provided temporary control function.
Definition SwerveDrivetrainImpl.hpp:374
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
Definition SwerveDrivetrainImpl.hpp:243
void ResetPose(Pose2d const &pose)
Resets the pose of the robot.
Definition SwerveDrivetrainImpl.hpp:468
void ResetTranslation(Translation2d const &translation)
Resets the translation of the robot pose without affecting rotation.
Definition SwerveDrivetrainImpl.hpp:484
void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrainImpl.hpp:570
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModuleImpl.hpp:29
Definition span.hpp:134
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:27
static constexpr int OK
No Error.
Definition StatusCodes.h:34
constexpr bool IsOK() const
Definition StatusCodes.h:859
Definition StatusCodes.h:18
Definition span.hpp:401
Common constants for a swerve drivetrain.
Definition SwerveDrivetrainConstants.hpp:19
Contains everything the control requests need to calculate the module state.
Definition SwerveDrivetrainImpl.hpp:147
units::second_t timestamp
The timestamp of the current control apply, in the timebase of utils::GetCurrentTime()
Definition SwerveDrivetrainImpl.hpp:162
units::meters_per_second_t kMaxSpeed
The max speed of the robot at 12 V output.
Definition SwerveDrivetrainImpl.hpp:153
units::second_t updatePeriod
The update period of control apply.
Definition SwerveDrivetrainImpl.hpp:164
ChassisSpeeds currentChassisSpeed
The current chassis speeds of the robot.
Definition SwerveDrivetrainImpl.hpp:158
impl::SwerveDriveKinematics * kinematics
The kinematics object used for control.
Definition SwerveDrivetrainImpl.hpp:149
Pose2d currentPose
The current pose of the robot.
Definition SwerveDrivetrainImpl.hpp:160
Rotation2d operatorForwardDirection
The forward direction from the operator perspective.
Definition SwerveDrivetrainImpl.hpp:156
Translation2d const * moduleLocations
The locations of the swerve modules.
Definition SwerveDrivetrainImpl.hpp:151
Plain-Old-Data class holding the state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:121
std::vector< SwerveModuleState > ModuleStates
The current module states.
Definition SwerveDrivetrainImpl.hpp:127
int32_t SuccessfulDaqs
Number of successful data acquisitions.
Definition SwerveDrivetrainImpl.hpp:139
ChassisSpeeds Speeds
The current velocity of the robot.
Definition SwerveDrivetrainImpl.hpp:125
units::second_t Timestamp
The timestamp of the state capture, in the timebase of utils::GetCurrentTime()
Definition SwerveDrivetrainImpl.hpp:135
std::vector< SwerveModulePosition > ModulePositions
The current module positions.
Definition SwerveDrivetrainImpl.hpp:131
Pose2d Pose
The current pose of the robot.
Definition SwerveDrivetrainImpl.hpp:123
std::vector< SwerveModuleState > ModuleTargets
The target module states.
Definition SwerveDrivetrainImpl.hpp:129
int32_t FailedDaqs
Number of failed data acquisitions.
Definition SwerveDrivetrainImpl.hpp:141
Rotation2d RawHeading
The raw heading of the robot, unaffected by vision updates and odometry resets.
Definition SwerveDrivetrainImpl.hpp:133
units::second_t OdometryPeriod
The measured odometry update period.
Definition SwerveDrivetrainImpl.hpp:137