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