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