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