CTRE Phoenix 6 C++ 26.50.0-alpha-1
Loading...
Searching...
No Matches
SwerveDrivetrain.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
15namespace ctre {
16namespace phoenix6 {
17namespace swerve {
18
19/**
20 * \brief Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
21 *
22 * This class handles the kinematics, configuration, and odometry of a
23 * swerve drive utilizing CTR Electronics devices. We recommend using
24 * the Swerve Project Generator in Tuner X to create a template project
25 * that demonstrates how to use this class.
26 *
27 * This class performs pose estimation internally using a separate odometry
28 * thread. Vision measurements can be added using AddVisionMeasurement.
29 * Other odometry APIs such as ResetPose are also available. The resulting
30 * pose estimate can be retrieved along with module states and other
31 * information using GetState. Additionally, the odometry thread synchronously
32 * provides all new state updates to a telemetry function registered with
33 * RegisterTelemetry.
34 *
35 * This class will construct the hardware devices internally, so the user
36 * only specifies the constants (IDs, PID gains, gear ratios, etc).
37 * Getters for these hardware devices are available.
38 *
39 * If using the generator, the order in which modules are constructed is
40 * Front Left, Front Right, Back Left, Back Right. This means if you need
41 * the Back Left module, call \c GetModule(2); to get the third (0-indexed)
42 * module.
43 */
44template <
45 std::derived_from<hardware::traits::CommonTalon> DriveMotorT,
46 std::derived_from<hardware::traits::CommonTalon> SteerMotorT,
47 typename EncoderT
48>
49 requires std::same_as<EncoderT, hardware::CANcoder> ||
50 std::same_as<EncoderT, hardware::CANdi> ||
51 std::same_as<EncoderT, hardware::TalonFXS>
53public:
54 /** \brief Performs swerve module updates in a separate thread to minimize latency. */
56
57 /**
58 * \brief Plain-Old-Data class holding the state of the swerve drivetrain.
59 * This encapsulates most data that is relevant for telemetry or
60 * decision-making from the Swerve Drive.
61 */
63
64 /**
65 * \brief Swerve Module class that encapsulates a swerve module powered by
66 * CTR Electronics devices.
67 *
68 * This class handles the hardware devices and configures them for
69 * swerve module operation using the Phoenix 6 API.
70 *
71 * This class constructs hardware devices internally, so the user
72 * only specifies the constants (IDs, PID gains, gear ratios, etc).
73 * Getters for these hardware devices are available.
74 */
76
77 /**
78 * \brief All constants for a swerve module.
79 */
81
82protected:
83 /** \brief Number of times to attempt config applies. */
84 static constexpr int kNumConfigAttempts = 2;
85
86 /** \brief The underlying drivetrain instance. */
88
89private:
90 std::vector<std::unique_ptr<SwerveModule>> _modules;
91
92 hardware::Pigeon2 _pigeon2;
94
95public:
96 /**
97 * \brief Constructs a CTRE SwerveDrivetrain using the specified constants.
98 *
99 * This constructs the underlying hardware devices, so users should not construct
100 * the devices themselves. If they need the devices, they can access them
101 * through getters in the classes.
102 *
103 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
104 * \param modules Constants for each specific module
105 */
106 template <std::same_as<SwerveModuleConstants>... ModuleConstants>
107 SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules) :
108 SwerveDrivetrain{drivetrainConstants, 0_Hz, modules...}
109 {}
110
111 /**
112 * \brief Constructs a CTRE SwerveDrivetrain using the specified constants.
113 *
114 * This constructs the underlying hardware devices, so users should not construct
115 * the devices themselves. If they need the devices, they can access them
116 * through getters in the classes.
117 *
118 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
119 * \param odometryUpdateFrequency The frequency to run the odometry loop. If
120 * unspecified or set to 0 Hz, this is 250 Hz on
121 * CAN FD, and 100 Hz on CAN 2.0.
122 * \param modules Constants for each specific module
123 */
124 template <std::same_as<SwerveModuleConstants>... ModuleConstants>
126 SwerveDrivetrainConstants const &drivetrainConstants,
127 wpi::units::hertz_t odometryUpdateFrequency,
128 ModuleConstants const &... modules
129 ) :
130 SwerveDrivetrain{drivetrainConstants, odometryUpdateFrequency, std::array{0.1, 0.1, 0.1}, std::array{0.9, 0.9, 0.9}, modules...}
131 {}
132
133 /**
134 * \brief Constructs a CTRE SwerveDrivetrain using the specified constants.
135 *
136 * This constructs the underlying hardware devices, so users should not construct
137 * the devices themselves. If they need the devices, they can access them
138 * through getters in the classes.
139 *
140 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
141 * \param odometryUpdateFrequency The frequency to run the odometry loop. If
142 * unspecified or set to 0 Hz, this is 250 Hz on
143 * CAN FD, and 100 Hz on CAN 2.0.
144 * \param odometryStandardDeviation The standard deviation for odometry calculation
145 * in the form [x, y, theta]ᵀ, with units in meters
146 * and radians
147 * \param visionStandardDeviation The standard deviation for vision calculation
148 * in the form [x, y, theta]ᵀ, with units in meters
149 * and radians
150 * \param modules Constants for each specific module
151 */
152 template <std::same_as<SwerveModuleConstants>... ModuleConstants>
154 SwerveDrivetrainConstants const &drivetrainConstants,
155 wpi::units::hertz_t odometryUpdateFrequency,
156 std::array<double, 3> const &odometryStandardDeviation,
157 std::array<double, 3> const &visionStandardDeviation,
158 ModuleConstants const &... modules
159 ) :
161 drivetrainConstants, odometryUpdateFrequency,
162 odometryStandardDeviation, visionStandardDeviation,
163 std::span<SwerveModuleConstants const>{std::array{modules...}}
164 },
165 _modules{CreateModuleArray(CANBus{drivetrainConstants.CANBusName}, modules...)},
166 _pigeon2{drivetrainConstants.Pigeon2Id, CANBus{drivetrainConstants.CANBusName}},
167 _simDrive{_drivetrain.GetModuleLocations(), _pigeon2.GetSimState(), modules...}
168 {
169 if (drivetrainConstants.Pigeon2Configs) {
170 ctre::phoenix::StatusCode retval{};
171 for (int i = 0; i < kNumConfigAttempts; ++i) {
172 retval = GetPigeon2().GetConfigurator().Apply(*drivetrainConstants.Pigeon2Configs);
173 if (retval.IsOK()) break;
174 }
175 if (!retval.IsOK()) {
176 printf("Pigeon2 ID %d failed config with error: %s\n", GetPigeon2().GetDeviceID(), retval.GetName());
177 }
178 }
179 /* do not start thread until after applying Pigeon 2 configs */
180 GetOdometryThread().Start();
181 }
182
183 virtual ~SwerveDrivetrain() = default;
184
185private:
186 template <typename... ModuleConstants>
187 std::vector<std::unique_ptr<SwerveModule>> CreateModuleArray(
188 CANBus canbus,
189 ModuleConstants const &... constants
190 ) {
191 std::vector<std::unique_ptr<SwerveModule>> modules;
192 modules.reserve(sizeof...(ModuleConstants));
193
194 [&]<size_t... Idxs>(std::index_sequence<Idxs...>) {
195 (modules.emplace_back(std::make_unique<SwerveModule>(constants, canbus, _drivetrain.GetModule(Idxs))), ...);
196 }(std::index_sequence_for<ModuleConstants...>{});
197
198 return modules;
199 }
200
201public:
202 /**
203 * \brief Updates all the simulation state variables for this
204 * drivetrain class. User provides the update variables for the simulation.
205 *
206 * \param dt time since last update call
207 * \param supplyVoltage voltage as seen at the motor controllers
208 */
209 virtual void UpdateSimState(wpi::units::second_t dt, wpi::units::volt_t supplyVoltage)
210 {
211 _simDrive.Update(dt, supplyVoltage, _modules);
212 }
213
214 /**
215 * \brief Optimizes the bus utilization of all devices in the swerve drivetrain by
216 * reducing the update frequencies of their status signals. All signals necessary
217 * for drivetrain functionality will remain enabled.
218 *
219 * This is equivalent to calling hardware#ParentDevice#OptimizeBusUtilizationForAll
220 * with all devices in the drivetrain.
221 *
222 * This will wait up to 0.100 seconds (100ms) for each status frame.
223 *
224 * \returns Status code of the first failed optimize call, or OK if all succeeded
225 */
227 {
228 std::vector<hardware::traits::CommonDevice *> devices;
229 devices.reserve(_modules.size() * 3 + 1);
230 devices.push_back(&GetPigeon2());
231 for (auto &module : _modules) {
232 devices.push_back(&module->GetDriveMotor());
233 devices.push_back(&module->GetSteerMotor());
234 devices.push_back(&module->GetEncoder());
235 }
237 }
238
239 /**
240 * \brief Optimizes the bus utilization of all devices in the swerve drivetrain by
241 * reducing the update frequencies of their status signals. All signals necessary
242 * for drivetrain functionality will remain enabled.
243 *
244 * This is equivalent to calling hardware#ParentDevice#OptimizeBusUtilizationForAll
245 * with all devices in the drivetrain.
246 *
247 * This will wait up to 0.100 seconds (100ms) for each status frame.
248 *
249 * \param optimizedFreqHz The update frequency to apply to the optimized status signals. A frequency
250 * of 0 Hz will turn off the signals. Otherwise, the minimum supported signal
251 * frequency is 4 Hz.
252 * \returns Status code of the first failed optimize call, or OK if all succeeded
253 */
254 ctre::phoenix::StatusCode OptimizeBusUtilization(wpi::units::hertz_t optimizedFreqHz)
255 {
256 std::vector<hardware::traits::CommonDevice *> devices;
257 devices.reserve(_modules.size() * 3 + 1);
258 devices.push_back(&GetPigeon2());
259 for (auto &module : _modules) {
260 devices.push_back(&module->GetDriveMotor());
261 devices.push_back(&module->GetSteerMotor());
262 devices.push_back(&module->GetEncoder());
263 }
264 return hardware::ParentDevice::OptimizeBusUtilizationForAll(optimizedFreqHz, devices);
265 }
266
267 /**
268 * \brief Gets whether the drivetrain is on a CAN FD bus.
269 *
270 * \returns true if on CAN FD
271 */
272 bool IsOnCANFD() const
273 {
274 return _drivetrain.IsOnCANFD();
275 }
276
277 /**
278 * \brief Gets the target odometry update frequency.
279 *
280 * \returns Target odometry update frequency
281 */
282 wpi::units::hertz_t GetOdometryFrequency() const
283 {
284 return _drivetrain.GetOdometryFrequency();
285 }
286
287 /**
288 * \brief Gets a reference to the odometry thread.
289 *
290 * \returns Odometry thread
291 */
293 {
294 return _drivetrain.GetOdometryThread();
295 }
296
297 /**
298 * \brief Check if the odometry is currently valid.
299 *
300 * \returns True if odometry is valid
301 */
302 virtual bool IsOdometryValid() const
303 {
304 return _drivetrain.IsOdometryValid();
305 }
306
307 /**
308 * \brief Gets a reference to the kinematics used for the drivetrain.
309 *
310 * \returns Swerve kinematics
311 */
313 {
314 return _drivetrain.GetKinematics();
315 }
316
317 /**
318 * \brief Applies the specified control request to this swerve drivetrain.
319 *
320 * This captures the swerve request by reference, so it must live for
321 * at least as long as the drivetrain. This can be done by storing the
322 * request as a member variable of your drivetrain subsystem or robot.
323 *
324 * \param request Request to apply
325 */
326 template <std::derived_from<requests::SwerveRequest> Request>
327 requires (!std::is_const_v<Request>)
328 void SetControl(Request &request)
329 {
330 _drivetrain.SetControl(
331 [&request](auto const &params, auto modules) mutable {
332 return request.Apply(params, modules);
333 }
334 );
335 }
336
337 /**
338 * \brief Applies the specified control request to this swerve drivetrain.
339 *
340 * \param request Request to apply
341 */
342 template <std::derived_from<requests::SwerveRequest> Request>
343 requires (!std::is_const_v<Request>)
344 void SetControl(Request &&request)
345 {
346 _drivetrain.SetControl(
347 [request=std::move(request)](auto const &params, auto modules) mutable {
348 return request.Apply(params, modules);
349 }
350 );
351 }
352
353 /**
354 * \brief Gets the current state of the swerve drivetrain.
355 * This includes information such as the pose estimate,
356 * module states, and chassis velocity.
357 *
358 * \returns Current state of the drivetrain
359 */
361 {
362 return _drivetrain.GetState();
363 }
364
365 /**
366 * \brief Register the specified lambda to be executed whenever the SwerveDriveState
367 * is updated in the odometry thread.
368 *
369 * It is imperative that this function is cheap, as it will be executed synchronously
370 * with the odometry call; if this takes a long time, it may negatively impact the
371 * odometry of this stack.
372 *
373 * This can also be used for logging data if the function performs logging instead of telemetry.
374 * Additionally, the SwerveDriveState object can be cloned and stored for later processing.
375 *
376 * \param telemetryFunction Function to call for telemetry or logging
377 */
378 virtual void RegisterTelemetry(std::function<void(SwerveDriveState const &)> telemetryFunction)
379 {
380 _drivetrain.RegisterTelemetry(std::move(telemetryFunction));
381 }
382
383 /**
384 * \brief Configures the neutral mode to use for all modules' drive motors.
385 *
386 * This will wait up to 0.100 seconds (100ms) by default.
387 *
388 * \param neutralMode The drive motor neutral mode
389 * \returns Status code of the first failed config call, or OK if all succeeded
390 */
392 {
393 return _drivetrain.ConfigNeutralMode(neutralMode);
394 }
395
396 /**
397 * \brief Configures the neutral mode to use for all modules' drive motors.
398 *
399 * \param neutralMode The drive motor neutral mode
400 * \param timeoutSeconds Maximum amount of time to wait when performing each configuration
401 * \returns Status code of the first failed config call, or OK if all succeeded
402 */
403 virtual ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode, wpi::units::second_t timeoutSeconds)
404 {
405 return _drivetrain.ConfigNeutralMode(neutralMode, timeoutSeconds);
406 }
407
408 /**
409 * \brief Zero's this swerve drive's odometry entirely.
410 *
411 * This will zero the entire odometry, and place the robot at 0,0
412 */
413 virtual void TareEverything()
414 {
415 _drivetrain.TareEverything();
416 }
417
418 /**
419 * \brief Resets the rotation of the robot pose to the given value
420 * from the requests#ForwardPerspectiveValue#OperatorPerspective
421 * perspective. This makes the current orientation of the robot minus
422 * `rotation` the X forward for field-centric maneuvers.
423 *
424 * This is equivalent to calling ResetRotation with `rotation +
425 * GetOperatorForwardDirection()`.
426 *
427 * \param rotation Rotation to make the current rotation
428 */
429 virtual void SeedFieldCentric(Rotation2d const &rotation = Rotation2d{})
430 {
431 _drivetrain.SeedFieldCentric(rotation);
432 }
433
434 /**
435 * \brief Resets the pose of the robot. The pose should be from the
436 * requests#ForwardPerspectiveValue#BlueAlliance perspective.
437 *
438 * \param pose Pose to make the current pose
439 */
440 virtual void ResetPose(Pose2d const &pose)
441 {
442 _drivetrain.ResetPose(pose);
443 }
444
445 /**
446 * \brief Resets the translation of the robot pose without affecting rotation.
447 * The translation should be from the requests#ForwardPerspectiveValue#BlueAlliance
448 * perspective.
449 *
450 * \param translation Translation to make the current translation
451 */
452 virtual void ResetTranslation(Translation2d const &translation)
453 {
454 _drivetrain.ResetTranslation(translation);
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 virtual void ResetRotation(Rotation2d const &rotation)
465 {
466 _drivetrain.ResetRotation(rotation);
467 }
468
469 /**
470 * \brief Takes the requests#ForwardPerspectiveValue#BlueAlliance perpective
471 * direction and treats it as the forward direction for
472 * requests#ForwardPerspectiveValue#OperatorPerspective.
473 *
474 * If the operator is in the Blue Alliance Station, this should be 0 degrees.
475 * If the operator is in the Red Alliance Station, this should be 180 degrees.
476 *
477 * This does not change the robot pose, which is in the
478 * requests#ForwardPerspectiveValue#BlueAlliance perspective.
479 * As a result, the robot pose may need to be reset using ResetPose.
480 *
481 * \param fieldDirection Heading indicating which direction is forward from
482 * the requests#ForwardPerspectiveValue#BlueAlliance perspective
483 */
484 virtual void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
485 {
486 _drivetrain.SetOperatorPerspectiveForward(fieldDirection);
487 }
488
489 /**
490 * \brief Returns the requests#ForwardPerspectiveValue#BlueAlliance perpective
491 * direction that is treated as the forward direction for
492 * requests#ForwardPerspectiveValue#OperatorPerspective.
493 *
494 * If the operator is in the Blue Alliance Station, this should be 0 degrees.
495 * If the operator is in the Red Alliance Station, this should be 180 degrees.
496 *
497 * \returns Heading indicating which direction is forward from
498 * the requests#ForwardPerspectiveValue#BlueAlliance perspective
499 */
501 {
502 return _drivetrain.GetOperatorForwardDirection();
503 }
504
505 /**
506 * \brief Adds a vision measurement to the Kalman Filter. This will correct the
507 * odometry pose estimate while still accounting for measurement noise.
508 *
509 * This method can be called as infrequently as you want
510 *
511 * To promote stability of the pose estimate and make it robust to bad vision
512 * data, we recommend only adding vision measurements that are already within
513 * one meter or so of the current pose estimate.
514 *
515 * \param visionRobotPose The pose of the robot as measured by the
516 * vision camera.
517 * \param timestamp The timestamp of the vision measurement in
518 * seconds. Note that you must use a timestamp with an
519 * epoch since system startup (i.e., the epoch of this
520 * timestamp is the same epoch as utils#GetCurrentTime).
521 * This means that you should use utils#GetCurrentTime
522 * as your time source in this case.
523 */
524 virtual void AddVisionMeasurement(Pose2d visionRobotPose, wpi::units::second_t timestamp)
525 {
526 _drivetrain.AddVisionMeasurement(std::move(visionRobotPose), timestamp);
527 }
528
529 /**
530 * \brief Adds a vision measurement to the Kalman Filter. This will correct the
531 * odometry pose estimate while still accounting for measurement noise.
532 *
533 * This method can be called as infrequently as you want.
534 *
535 * To promote stability of the pose estimate and make it robust to bad vision
536 * data, we recommend only adding vision measurements that are already within
537 * one meter or so of the current pose estimate.
538 *
539 * Note that the vision measurement standard deviations passed into this method
540 * will continue to apply to future measurements until a subsequent call to
541 * #SetVisionMeasurementStdDevs or this method.
542 *
543 * \param visionRobotPose The pose of the robot as measured by the
544 * vision camera.
545 * \param timestamp The timestamp of the vision measurement in
546 * seconds. Note that you must use a timestamp with an
547 * epoch since system startup (i.e., the epoch of this
548 * timestamp is the same epoch as utils#GetCurrentTime).
549 * This means that you should use utils#GetCurrentTime
550 * as your time source in this case.
551 * \param visionMeasurementStdDevs Standard deviations of the vision pose
552 * measurement (x position in meters, y position
553 * in meters, and heading in radians). Increase
554 * these numbers to trust the vision pose
555 * measurement less.
556 */
558 Pose2d visionRobotPose,
559 wpi::units::second_t timestamp,
560 std::array<double, 3> visionMeasurementStdDevs)
561 {
562 _drivetrain.AddVisionMeasurement(std::move(visionRobotPose), timestamp, visionMeasurementStdDevs);
563 }
564
565 /**
566 * \brief Sets the pose estimator's trust of global measurements. This might be used to
567 * change trust in vision measurements after the autonomous period, or to change
568 * trust as distance to a vision target increases.
569 *
570 * \param visionMeasurementStdDevs Standard deviations of the vision
571 * measurements. Increase these
572 * numbers to trust global measurements from
573 * vision less. This matrix is in the form [x,
574 * y, theta]ᵀ, with units in meters and radians.
575 */
576 virtual void SetVisionMeasurementStdDevs(std::array<double, 3> visionMeasurementStdDevs)
577 {
578 _drivetrain.SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
579 }
580
581 /**
582 * \brief Sets the pose estimator's trust in robot odometry. This might be used
583 * to change trust in odometry after an impact with the wall or traversing a bump.
584 *
585 * \param stateStdDevs Standard deviations of the pose estimate. Increase these
586 * numbers to trust your state estimate less. This matrix is
587 * in the form [x, y, theta]ᵀ, with units in meters and radians.
588 */
589 virtual void SetStateStdDevs(std::array<double, 3> const &stateStdDevs)
590 {
591 _drivetrain.SetStateStdDevs(stateStdDevs);
592 }
593
594 /**
595 * \brief Return the pose at a given timestamp, if the buffer is not empty.
596 *
597 * \param timestamp The pose's timestamp. Note that you must use a timestamp
598 * with an epoch since system startup (i.e., the epoch of
599 * this 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 * \returns The pose at the given timestamp (or std::nullopt if the buffer is
603 * empty).
604 */
605 virtual std::optional<Pose2d> SamplePoseAt(wpi::units::second_t timestamp) const
606 {
607 return _drivetrain.SamplePoseAt(timestamp);
608 }
609
610 /**
611 * \brief Get a reference to the module at the specified index.
612 * The index corresponds to the module described in the constructor.
613 *
614 * \param index Which module to get
615 * \returns Reference to SwerveModule
616 */
617 SwerveModule &GetModule(size_t index)
618 {
619 return *_modules.at(index);
620 }
621 /**
622 * \brief Get a reference to the module at the specified index.
623 * The index corresponds to the module described in the constructor.
624 *
625 * \param index Which module to get
626 * \returns Reference to SwerveModule
627 */
628 SwerveModule const &GetModule(size_t index) const
629 {
630 return *_modules.at(index);
631 }
632 /**
633 * \brief Get a reference to the full array of modules.
634 * The indexes correspond to the module described in the constructor.
635 *
636 * \returns Reference to the SwerveModule array
637 */
638 std::span<std::unique_ptr<SwerveModule> const> GetModules() const
639 {
640 return _modules;
641 }
642
643 /**
644 * \brief Gets the locations of the swerve modules.
645 *
646 * \returns Reference to the array of swerve module locations
647 */
648 std::vector<Translation2d> const &GetModuleLocations() const { return _drivetrain.GetModuleLocations(); }
649
650 /**
651 * \brief Gets the current orientation of the robot as a wpi#math#Rotation3d from
652 * the Pigeon 2 quaternion values.
653 *
654 * \returns The robot orientation as a wpi#math#Rotation3d
655 */
656 virtual wpi::math::Rotation3d GetRotation3d() const
657 {
658 return _pigeon2.GetRotation3d();
659 }
660
661 /**
662 * \brief Gets this drivetrain's Pigeon 2 reference.
663 *
664 * This should be used only to access signals and change configurations that the
665 * swerve drivetrain does not configure itself.
666 *
667 * \returns This drivetrain's Pigeon 2 reference
668 */
670 {
671 return _pigeon2;
672 }
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 */
682 {
683 return _pigeon2;
684 }
685};
686
687}
688}
689}
Class for getting information about an available CAN bus.
Definition CANBus.hpp:19
static ctre::phoenix::StatusCode OptimizeBusUtilizationForAll(Devices &... devices)
Optimizes the bus utilization of the provided devices by reducing the update frequencies of their sta...
Definition ParentDevice.hpp:287
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition Pigeon2.hpp:27
Simplified swerve drive simulation class.
Definition SimSwerveDrivetrain.hpp:42
virtual void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the f...
Definition SwerveDrivetrain.hpp:484
virtual ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode, wpi::units::second_t timeoutSeconds)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrain.hpp:403
OdometryThread & GetOdometryThread()
Gets a reference to the odometry thread.
Definition SwerveDrivetrain.hpp:292
virtual void UpdateSimState(wpi::units::second_t dt, wpi::units::volt_t supplyVoltage)
Updates all the simulation state variables for this drivetrain class.
Definition SwerveDrivetrain.hpp:209
virtual void ResetTranslation(Translation2d const &translation)
Resets the translation of the robot pose without affecting rotation.
Definition SwerveDrivetrain.hpp:452
virtual void TareEverything()
Zero's this swerve drive's odometry entirely.
Definition SwerveDrivetrain.hpp:413
ctre::phoenix::StatusCode OptimizeBusUtilization()
Optimizes the bus utilization of all devices in the swerve drivetrain by reducing the update frequenc...
Definition SwerveDrivetrain.hpp:226
impl::SwerveDrivetrainImpl::OdometryThread OdometryThread
Performs swerve module updates in a separate thread to minimize latency.
Definition SwerveDrivetrain.hpp:55
swerve::SwerveModule< DriveMotorT, SteerMotorT, EncoderT > SwerveModule
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveDrivetrain.hpp:75
virtual std::optional< Pose2d > SamplePoseAt(wpi::units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
Definition SwerveDrivetrain.hpp:605
virtual void SetStateStdDevs(std::array< double, 3 > const &stateStdDevs)
Sets the pose estimator's trust in robot odometry.
Definition SwerveDrivetrain.hpp:589
SwerveModule const & GetModule(size_t index) const
Get a reference to the module at the specified index.
Definition SwerveDrivetrain.hpp:628
ctre::phoenix::StatusCode OptimizeBusUtilization(wpi::units::hertz_t optimizedFreqHz)
Optimizes the bus utilization of all devices in the swerve drivetrain by reducing the update frequenc...
Definition SwerveDrivetrain.hpp:254
SwerveModule & GetModule(size_t index)
Get a reference to the module at the specified index.
Definition SwerveDrivetrain.hpp:617
std::span< std::unique_ptr< SwerveModule > const > GetModules() const
Get a reference to the full array of modules.
Definition SwerveDrivetrain.hpp:638
void SetControl(Request &request)
Applies the specified control request to this swerve drivetrain.
Definition SwerveDrivetrain.hpp:328
virtual void AddVisionMeasurement(Pose2d visionRobotPose, wpi::units::second_t timestamp, std::array< double, 3 > visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrain.hpp:557
void SetControl(Request &&request)
Applies the specified control request to this swerve drivetrain.
Definition SwerveDrivetrain.hpp:344
virtual bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrain.hpp:302
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, wpi::units::hertz_t odometryUpdateFrequency, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:125
virtual void AddVisionMeasurement(Pose2d visionRobotPose, wpi::units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrain.hpp:524
virtual wpi::math::Rotation3d GetRotation3d() const
Gets the current orientation of the robot as a wpi::math::Rotation3d from the Pigeon 2 quaternion val...
Definition SwerveDrivetrain.hpp:656
impl::SwerveDriveKinematics const & GetKinematics() const
Gets a reference to the kinematics used for the drivetrain.
Definition SwerveDrivetrain.hpp:312
virtual ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrain.hpp:391
SwerveDriveState GetState() const
Gets the current state of the swerve drivetrain.
Definition SwerveDrivetrain.hpp:360
virtual void SeedFieldCentric(Rotation2d const &rotation=Rotation2d{})
Resets the rotation of the robot pose to the given value from the requests::ForwardPerspectiveValue::...
Definition SwerveDrivetrain.hpp:429
virtual void SetVisionMeasurementStdDevs(std::array< double, 3 > visionMeasurementStdDevs)
Sets the pose estimator's trust of global measurements.
Definition SwerveDrivetrain.hpp:576
virtual void ResetPose(Pose2d const &pose)
Resets the pose of the robot.
Definition SwerveDrivetrain.hpp:440
bool IsOnCANFD() const
Gets whether the drivetrain is on a CAN FD bus.
Definition SwerveDrivetrain.hpp:272
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:107
impl::SwerveDrivetrainImpl::SwerveDriveState SwerveDriveState
Plain-Old-Data class holding the state of the swerve drivetrain.
Definition SwerveDrivetrain.hpp:62
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, wpi::units::hertz_t odometryUpdateFrequency, std::array< double, 3 > const &odometryStandardDeviation, std::array< double, 3 > const &visionStandardDeviation, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:153
SwerveModule::Constants SwerveModuleConstants
All constants for a swerve module.
Definition SwerveDrivetrain.hpp:80
virtual void ResetRotation(Rotation2d const &rotation)
Resets the rotation of the robot pose without affecting translation.
Definition SwerveDrivetrain.hpp:464
hardware::Pigeon2 & GetPigeon2()
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrain.hpp:669
hardware::Pigeon2 const & GetPigeon2() const
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrain.hpp:681
wpi::units::hertz_t GetOdometryFrequency() const
Gets the target odometry update frequency.
Definition SwerveDrivetrain.hpp:282
static constexpr int kNumConfigAttempts
Number of times to attempt config applies.
Definition SwerveDrivetrain.hpp:84
virtual void RegisterTelemetry(std::function< void(SwerveDriveState const &)> telemetryFunction)
Register the specified lambda to be executed whenever the SwerveDriveState is updated in the odometry...
Definition SwerveDrivetrain.hpp:378
impl::SwerveDrivetrainImpl _drivetrain
The underlying drivetrain instance.
Definition SwerveDrivetrain.hpp:87
std::vector< Translation2d > const & GetModuleLocations() const
Gets the locations of the swerve modules.
Definition SwerveDrivetrain.hpp:648
Rotation2d GetOperatorForwardDirection() const
Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as t...
Definition SwerveDrivetrain.hpp:500
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModule.hpp:52
SwerveModuleConstants< typename DriveMotorT::Configuration, typename SteerMotorT::Configuration, typename EncoderT::Configuration > Constants
All constants for a swerve module.
Definition SwerveModule.hpp:62
Class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states ...
Definition SwerveDriveKinematics.hpp:41
Performs swerve module updates in a separate thread to minimize latency.
Definition SwerveDrivetrainImpl.hpp:33
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrainImpl.hpp:30
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:28
constexpr const char * GetName() const
Gets the name of this StatusCode.
Definition StatusCodes.h:867
constexpr bool IsOK() const
Definition StatusCodes.h:860
Definition SwerveModule.hpp:28
Definition ExternalFeedbackConfigs.hpp:16
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
Plain-Old-Data class holding the state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:116