CTRE Phoenix 6 C++ 26.3.0
Loading...
Searching...
No Matches
SwerveRequest.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
11
12namespace ctre {
13namespace phoenix6 {
14namespace swerve {
15namespace requests {
16
17/**
18 * \brief In field-centric control, the direction of "forward" is sometimes different
19 * depending on perspective. This addresses which forward to use.
20 */
22 /**
23 * \brief "Forward" (positive X) is determined from the operator's perspective.
24 * This is important for most teleop driven field-centric requests, where positive
25 * X means to drive away from the operator.
26 *
27 * Important: Users must specify the OperatorPerspective in the SwerveDrivetrain object
28 */
30 /**
31 * \brief "Forward" (positive X) is always from the perspective of the blue alliance (i.e.
32 * towards the red alliance). This is important in situations such as path following where
33 * positive X is always from the blue alliance perspective, regardless of where the operator
34 * is physically located.
35 */
36 BlueAlliance = 1,
37};
38
39/**
40 * \brief In field-centric control, the direction of "forward" for the target direction
41 * sometimes differs from "forward" for translation. This addresses which forward to use.
42 */
44 /**
45 * \brief Match the ForwardPerspective parameter for heading control.
46 */
48 /**
49 * \brief "Forward" (0 deg) is always from the perspective of the blue alliance (i.e.
50 * towards the red alliance). This can be used to allow for the robot rotation to track
51 * vision targets while using operator-perspective joystick control for translation.
52 */
53 BlueAlliance = 1,
54};
55
56/**
57 * \brief Container for all the Swerve Requests. Use this to find all applicable swerve
58 * drive requests.
59 *
60 * This is also an interface common to all swerve drive control requests that
61 * allow the request to calculate the state to apply to the modules.
62 */
64public:
66
67 virtual ~SwerveRequest() = default;
68
69 /**
70 * \brief Applies this swerve request to the given modules.
71 * This is typically called by the SwerveDrivetrain.
72 *
73 * \param parameters Parameters the control request needs to calculate the module state
74 * \param modulesToApply Modules to which the control request is applied
75 * \returns Status code of sending the request
76 */
77 virtual ctre::phoenix::StatusCode Apply(ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) = 0;
78};
79
80/**
81 * \brief Does nothing to the swerve module state. This is the default state of a newly
82 * created swerve drive mechanism.
83 */
84class Idle : public SwerveRequest {
85public:
86 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> ) override
87 {
89 }
90};
91
92/**
93 * \brief Sets the swerve drive module states to point inward on the
94 * robot in an "X" fashion, creating a natural brake which will
95 * oppose any motion.
96 */
98public:
99 /**
100 * \brief The type of control request to use for the drive motor.
101 */
103 /**
104 * \brief The type of control request to use for the steer motor.
105 */
107
108 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
109 {
110 auto moduleRequest = impl::SwerveModuleImpl::ModuleRequest{}
113 .WithUpdatePeriod(parameters.updatePeriod);
114 for (size_t i = 0; i < modulesToApply.size(); ++i) {
115 modulesToApply[i]->Apply(moduleRequest.WithState({0_mps, parameters.moduleLocations[i].Angle()}));
116 }
117
119 }
120
121 /**
122 * \brief Modifies the DriveRequestType parameter and returns itself.
123 *
124 * The type of control request to use for the drive motor.
125 *
126 * \param newDriveRequestType Parameter to modify
127 * \returns this object
128 */
130 {
131 this->DriveRequestType = std::move(newDriveRequestType);
132 return *this;
133 }
134 /**
135 * \brief Modifies the DriveRequestType parameter and returns itself.
136 *
137 * The type of control request to use for the drive motor.
138 *
139 * \param newDriveRequestType Parameter to modify
140 * \returns this object
141 */
143 {
144 this->DriveRequestType = std::move(newDriveRequestType);
145 return std::move(*this);
146 }
147
148 /**
149 * \brief Modifies the SteerRequestType parameter and returns itself.
150 *
151 * The type of control request to use for the steer motor.
152 *
153 * \param newSteerRequestType Parameter to modify
154 * \returns this object
155 */
157 {
158 this->SteerRequestType = std::move(newSteerRequestType);
159 return *this;
160 }
161 /**
162 * \brief Modifies the SteerRequestType parameter and returns itself.
163 *
164 * The type of control request to use for the steer motor.
165 *
166 * \param newSteerRequestType Parameter to modify
167 * \returns this object
168 */
170 {
171 this->SteerRequestType = std::move(newSteerRequestType);
172 return std::move(*this);
173 }
174};
175
176/**
177 * \brief Drives the swerve drivetrain in a field-centric manner. This request
178 * is optimized for joystick control during teleop with built-in deadbands.
179 *
180 * This request specifies the direction the robot should travel oriented against
181 * the field, and the rate at which their robot should rotate about the center
182 * of the robot.
183 *
184 * An example scenario is that the robot is oriented to the field +Y (left), the
185 * VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s. In
186 * this scenario, the robot would drive along the field +X (forward) at 5 m/s
187 * and turn counterclockwise at 0.5 rad/s.
188 */
190public:
191 /**
192 * \brief The velocity in the X direction. X is defined as forward according
193 * toWPILib convention, so this determines how fast to travel forward.
194 */
195 units::meters_per_second_t VelocityX = 0_mps;
196 /**
197 * \brief The velocity in the Y direction. Y is defined as to the left
198 * according to WPILib convention, so this determines how fast to travel to
199 * the left.
200 */
201 units::meters_per_second_t VelocityY = 0_mps;
202 /**
203 * \brief The angular rate to rotate at. Angular rate is defined as
204 * counterclockwise positive, so this determines how fast to turn
205 * counterclockwise.
206 */
207 units::radians_per_second_t RotationalRate = 0_rad_per_s;
208 /**
209 * \brief The allowable deadband of the request.
210 */
211 units::meters_per_second_t Deadband = 0_mps;
212 /**
213 * \brief The rotational deadband of the request.
214 */
215 units::radians_per_second_t RotationalDeadband = 0_rad_per_s;
216 /**
217 * \brief The center of rotation the robot should rotate around. This is
218 * (0,0) by default, which will rotate around the center of the robot.
219 */
220 Translation2d CenterOfRotation{};
221
222 /**
223 * \brief The type of control request to use for the drive motor.
224 */
226 /**
227 * \brief The type of control request to use for the steer motor.
228 */
230 /**
231 * \brief Whether to desaturate wheel speeds before applying.
232 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
233 */
235
236 /**
237 * \brief The perspective to use when determining which direction is forward.
238 */
240
241 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
242 {
243 auto toApplyX = VelocityX;
244 auto toApplyY = VelocityY;
245 auto toApplyOmega = RotationalRate;
246
248 /* If we're operator perspective, modify the X/Y translation by the angle */
249 Translation2d tmp{toApplyX * 1_s, toApplyY * 1_s};
250 tmp = tmp.RotateBy(parameters.operatorForwardDirection);
251 toApplyX = tmp.X() / 1_s;
252 toApplyY = tmp.Y() / 1_s;
253 }
254
255 if (units::math::hypot(toApplyX, toApplyY) < Deadband) {
256 toApplyX = 0_mps;
257 toApplyY = 0_mps;
258 }
259 if (units::math::abs(toApplyOmega) < RotationalDeadband) {
260 toApplyOmega = 0_rad_per_s;
261 }
262
263 auto const speeds = ChassisSpeeds::Discretize(
264 ChassisSpeeds::FromFieldRelativeSpeeds(
265 {toApplyX, toApplyY, toApplyOmega}, parameters.currentPose.Rotation()
266 ),
267 parameters.updatePeriod
268 );
269
270 auto states = parameters.kinematics->ToSwerveModuleStates(speeds, CenterOfRotation);
271 if (DesaturateWheelSpeeds && parameters.kMaxSpeed > 0_mps) {
273 }
274
275 auto moduleRequest = impl::SwerveModuleImpl::ModuleRequest{}
278 .WithUpdatePeriod(parameters.updatePeriod);
279 for (size_t i = 0; i < modulesToApply.size(); ++i) {
280 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
281 }
282
284 }
285
286 /**
287 * \brief Modifies the VelocityX parameter and returns itself.
288 *
289 * The velocity in the X direction. X is defined as forward according to
290 * WPILib convention, so this determines how fast to travel forward.
291 *
292 * \param newVelocityX Parameter to modify
293 * \returns this object
294 */
295 FieldCentric &WithVelocityX(units::meters_per_second_t newVelocityX) &
296 {
297 this->VelocityX = std::move(newVelocityX);
298 return *this;
299 }
300 /**
301 * \brief Modifies the VelocityX parameter and returns itself.
302 *
303 * The velocity in the X direction. X is defined as forward according to
304 * WPILib convention, so this determines how fast to travel forward.
305 *
306 * \param newVelocityX Parameter to modify
307 * \returns this object
308 */
309 FieldCentric &&WithVelocityX(units::meters_per_second_t newVelocityX) &&
310 {
311 this->VelocityX = std::move(newVelocityX);
312 return std::move(*this);
313 }
314
315 /**
316 * \brief Modifies the VelocityY parameter and returns itself.
317 *
318 * The velocity in the Y direction. Y is defined as to the left according
319 * to WPILib convention, so this determines how fast to travel to the
320 * left.
321 *
322 * \param newVelocityY Parameter to modify
323 * \returns this object
324 */
325 FieldCentric &WithVelocityY(units::meters_per_second_t newVelocityY) &
326 {
327 this->VelocityY = std::move(newVelocityY);
328 return *this;
329 }
330 /**
331 * \brief Modifies the VelocityY parameter and returns itself.
332 *
333 * The velocity in the Y direction. Y is defined as to the left according
334 * to WPILib convention, so this determines how fast to travel to the
335 * left.
336 *
337 * \param newVelocityY Parameter to modify
338 * \returns this object
339 */
340 FieldCentric &&WithVelocityY(units::meters_per_second_t newVelocityY) &&
341 {
342 this->VelocityY = std::move(newVelocityY);
343 return std::move(*this);
344 }
345
346 /**
347 * \brief Modifies the RotationalRate parameter and returns itself.
348 *
349 * The angular rate to rotate at. Angular rate is defined as counterclockwise
350 * positive, so this determines how fast to turn counterclockwise.
351 *
352 * \param newRotationalRate Parameter to modify
353 * \returns this object
354 */
355 FieldCentric &WithRotationalRate(units::radians_per_second_t newRotationalRate) &
356 {
357 this->RotationalRate = std::move(newRotationalRate);
358 return *this;
359 }
360 /**
361 * \brief Modifies the RotationalRate parameter and returns itself.
362 *
363 * The angular rate to rotate at. Angular rate is defined as counterclockwise
364 * positive, so this determines how fast to turn counterclockwise.
365 *
366 * \param newRotationalRate Parameter to modify
367 * \returns this object
368 */
369 FieldCentric &&WithRotationalRate(units::radians_per_second_t newRotationalRate) &&
370 {
371 this->RotationalRate = std::move(newRotationalRate);
372 return std::move(*this);
373 }
374
375 /**
376 * \brief Modifies the Deadband parameter and returns itself.
377 *
378 * The allowable deadband of the request.
379 *
380 * \param newDeadband Parameter to modify
381 * \returns this object
382 */
383 FieldCentric &WithDeadband(units::meters_per_second_t newDeadband) &
384 {
385 this->Deadband = std::move(newDeadband);
386 return *this;
387 }
388 /**
389 * \brief Modifies the Deadband parameter and returns itself.
390 *
391 * The allowable deadband of the request.
392 *
393 * \param newDeadband Parameter to modify
394 * \returns this object
395 */
396 FieldCentric &&WithDeadband(units::meters_per_second_t newDeadband) &&
397 {
398 this->Deadband = std::move(newDeadband);
399 return std::move(*this);
400 }
401
402 /**
403 * \brief Modifies the RotationalDeadband parameter and returns itself.
404 *
405 * The rotational deadband of the request.
406 *
407 * \param newRotationalDeadband Parameter to modify
408 * \returns this object
409 */
410 FieldCentric &WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &
411 {
412 this->RotationalDeadband = std::move(newRotationalDeadband);
413 return *this;
414 }
415 /**
416 * \brief Modifies the RotationalDeadband parameter and returns itself.
417 *
418 * The rotational deadband of the request.
419 *
420 * \param newRotationalDeadband Parameter to modify
421 * \returns this object
422 */
423 FieldCentric &&WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &&
424 {
425 this->RotationalDeadband = std::move(newRotationalDeadband);
426 return std::move(*this);
427 }
428
429 /**
430 * \brief Modifies the CenterOfRotation parameter and returns itself.
431 *
432 * The center of rotation the robot should rotate around. This is (0,0) by
433 * default, which will rotate around the center of the robot.
434 *
435 * \param newCenterOfRotation Parameter to modify
436 * \returns this object
437 */
438 FieldCentric &WithCenterOfRotation(Translation2d newCenterOfRotation) &
439 {
440 this->CenterOfRotation = std::move(newCenterOfRotation);
441 return *this;
442 }
443 /**
444 * \brief Modifies the CenterOfRotation parameter and returns itself.
445 *
446 * The center of rotation the robot should rotate around. This is (0,0) by
447 * default, which will rotate around the center of the robot.
448 *
449 * \param newCenterOfRotation Parameter to modify
450 * \returns this object
451 */
452 FieldCentric &&WithCenterOfRotation(Translation2d newCenterOfRotation) &&
453 {
454 this->CenterOfRotation = std::move(newCenterOfRotation);
455 return std::move(*this);
456 }
457
458 /**
459 * \brief Modifies the DriveRequestType parameter and returns itself.
460 *
461 * The type of control request to use for the drive motor.
462 *
463 * \param newDriveRequestType Parameter to modify
464 * \returns this object
465 */
467 {
468 this->DriveRequestType = std::move(newDriveRequestType);
469 return *this;
470 }
471 /**
472 * \brief Modifies the DriveRequestType parameter and returns itself.
473 *
474 * The type of control request to use for the drive motor.
475 *
476 * \param newDriveRequestType Parameter to modify
477 * \returns this object
478 */
480 {
481 this->DriveRequestType = std::move(newDriveRequestType);
482 return std::move(*this);
483 }
484
485 /**
486 * \brief Modifies the SteerRequestType parameter and returns itself.
487 *
488 * The type of control request to use for the steer motor.
489 *
490 * \param newSteerRequestType Parameter to modify
491 * \returns this object
492 */
494 {
495 this->SteerRequestType = std::move(newSteerRequestType);
496 return *this;
497 }
498 /**
499 * \brief Modifies the SteerRequestType parameter and returns itself.
500 *
501 * The type of control request to use for the steer motor.
502 *
503 * \param newSteerRequestType Parameter to modify
504 * \returns this object
505 */
507 {
508 this->SteerRequestType = std::move(newSteerRequestType);
509 return std::move(*this);
510 }
511
512 /**
513 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
514 *
515 * Whether to desaturate wheel speeds before applying. For more information, see
516 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
517 *
518 * \param newDesaturateWheelSpeeds Parameter to modify
519 * \returns this object
520 */
521 FieldCentric &WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
522 {
523 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
524 return *this;
525 }
526 /**
527 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
528 *
529 * Whether to desaturate wheel speeds before applying. For more information, see
530 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
531 *
532 * \param newDesaturateWheelSpeeds Parameter to modify
533 * \returns this object
534 */
535 FieldCentric &&WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
536 {
537 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
538 return std::move(*this);
539 }
540
541 /**
542 * \brief Modifies the ForwardPerspective parameter and returns itself.
543 *
544 * The perspective to use when determining which direction is forward.
545 *
546 * \param newForwardPerspective Parameter to modify
547 * \returns this object
548 */
550 {
551 this->ForwardPerspective = std::move(newForwardPerspective);
552 return *this;
553 }
554 /**
555 * \brief Modifies the ForwardPerspective parameter and returns itself.
556 *
557 * The perspective to use when determining which direction is forward.
558 *
559 * \param newForwardPerspective Parameter to modify
560 * \returns this object
561 */
563 {
564 this->ForwardPerspective = std::move(newForwardPerspective);
565 return std::move(*this);
566 }
567};
568
569/**
570 * \brief Drives the swerve drivetrain in a robot-centric manner. This request
571 * is optimized for joystick control during teleop with built-in deadbands.
572 *
573 * This request specifies the direction the robot should travel oriented against
574 * the robot itself, and the rate at which their robot should rotate about the
575 * center of the robot.
576 *
577 * An example scenario is that the robot is oriented to the field +Y (left), the
578 * VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s. In
579 * this scenario, the robot would drive forward relative to itself (or left
580 * along the field +Y) at 5 m/s and turn counterclockwise at 0.5 rad/s.
581 */
583public:
584 /**
585 * \brief The velocity in the X direction. X is defined as forward according
586 * toWPILib convention, so this determines how fast to travel forward.
587 */
588 units::meters_per_second_t VelocityX = 0_mps;
589 /**
590 * \brief The velocity in the Y direction. Y is defined as to the left
591 * according to WPILib convention, so this determines how fast to travel to
592 * the left.
593 */
594 units::meters_per_second_t VelocityY = 0_mps;
595 /**
596 * \brief The angular rate to rotate at. Angular rate is defined as
597 * counterclockwise positive, so this determines how fast to turn
598 * counterclockwise.
599 */
600 units::radians_per_second_t RotationalRate = 0_rad_per_s;
601
602 /**
603 * \brief The allowable deadband of the request.
604 */
605 units::meters_per_second_t Deadband = 0_mps;
606 /**
607 * \brief The rotational deadband of the request.
608 */
609 units::radians_per_second_t RotationalDeadband = 0_rad_per_s;
610 /**
611 * \brief The center of rotation the robot should rotate around. This is
612 * (0,0) by default, which will rotate around the center of the robot.
613 */
614 Translation2d CenterOfRotation{};
615
616 /**
617 * \brief The type of control request to use for the drive motor.
618 */
620 /**
621 * \brief The type of control request to use for the steer motor.
622 */
624 /**
625 * \brief Whether to desaturate wheel speeds before applying.
626 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
627 */
629
630 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
631 {
632 auto toApplyX = VelocityX;
633 auto toApplyY = VelocityY;
634 auto toApplyOmega = RotationalRate;
635 if (units::math::hypot(toApplyX, toApplyY) < Deadband) {
636 toApplyX = 0_mps;
637 toApplyY = 0_mps;
638 }
639 if (units::math::abs(toApplyOmega) < RotationalDeadband) {
640 toApplyOmega = 0_rad_per_s;
641 }
642 ChassisSpeeds const speeds{toApplyX, toApplyY, toApplyOmega};
643
644 auto states = parameters.kinematics->ToSwerveModuleStates(speeds, CenterOfRotation);
645 if (DesaturateWheelSpeeds && parameters.kMaxSpeed > 0_mps) {
647 }
648
649 auto moduleRequest = impl::SwerveModuleImpl::ModuleRequest{}
652 .WithUpdatePeriod(parameters.updatePeriod);
653 for (size_t i = 0; i < modulesToApply.size(); ++i) {
654 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
655 }
656
658 }
659
660 /**
661 * \brief Modifies the VelocityX parameter and returns itself.
662 *
663 * The velocity in the X direction. X is defined as forward according to
664 * WPILib convention, so this determines how fast to travel forward.
665 *
666 * \param newVelocityX Parameter to modify
667 * \returns this object
668 */
669 RobotCentric &WithVelocityX(units::meters_per_second_t newVelocityX) &
670 {
671 this->VelocityX = std::move(newVelocityX);
672 return *this;
673 }
674 /**
675 * \brief Modifies the VelocityX parameter and returns itself.
676 *
677 * The velocity in the X direction. X is defined as forward according to
678 * WPILib convention, so this determines how fast to travel forward.
679 *
680 * \param newVelocityX Parameter to modify
681 * \returns this object
682 */
683 RobotCentric &&WithVelocityX(units::meters_per_second_t newVelocityX) &&
684 {
685 this->VelocityX = std::move(newVelocityX);
686 return std::move(*this);
687 }
688
689 /**
690 * \brief Modifies the VelocityY parameter and returns itself.
691 *
692 * The velocity in the Y direction. Y is defined as to the left according
693 * to WPILib convention, so this determines how fast to travel to the
694 * left.
695 *
696 * \param newVelocityY Parameter to modify
697 * \returns this object
698 */
699 RobotCentric &WithVelocityY(units::meters_per_second_t newVelocityY) &
700 {
701 this->VelocityY = std::move(newVelocityY);
702 return *this;
703 }
704 /**
705 * \brief Modifies the VelocityY parameter and returns itself.
706 *
707 * The velocity in the Y direction. Y is defined as to the left according
708 * to WPILib convention, so this determines how fast to travel to the
709 * left.
710 *
711 * \param newVelocityY Parameter to modify
712 * \returns this object
713 */
714 RobotCentric &&WithVelocityY(units::meters_per_second_t newVelocityY) &&
715 {
716 this->VelocityY = std::move(newVelocityY);
717 return std::move(*this);
718 }
719
720 /**
721 * \brief Modifies the RotationalRate parameter and returns itself.
722 *
723 * The angular rate to rotate at. Angular rate is defined as counterclockwise
724 * positive, so this determines how fast to turn counterclockwise.
725 *
726 * \param newRotationalRate Parameter to modify
727 * \returns this object
728 */
729 RobotCentric &WithRotationalRate(units::radians_per_second_t newRotationalRate) &
730 {
731 this->RotationalRate = std::move(newRotationalRate);
732 return *this;
733 }
734 /**
735 * \brief Modifies the RotationalRate parameter and returns itself.
736 *
737 * The angular rate to rotate at. Angular rate is defined as counterclockwise
738 * positive, so this determines how fast to turn counterclockwise.
739 *
740 * \param newRotationalRate Parameter to modify
741 * \returns this object
742 */
743 RobotCentric &&WithRotationalRate(units::radians_per_second_t newRotationalRate) &&
744 {
745 this->RotationalRate = std::move(newRotationalRate);
746 return std::move(*this);
747 }
748
749 /**
750 * \brief Modifies the Deadband parameter and returns itself.
751 *
752 * The allowable deadband of the request.
753 *
754 * \param newDeadband Parameter to modify
755 * \returns this object
756 */
757 RobotCentric &WithDeadband(units::meters_per_second_t newDeadband) &
758 {
759 this->Deadband = std::move(newDeadband);
760 return *this;
761 }
762 /**
763 * \brief Modifies the Deadband parameter and returns itself.
764 *
765 * The allowable deadband of the request.
766 *
767 * \param newDeadband Parameter to modify
768 * \returns this object
769 */
770 RobotCentric &&WithDeadband(units::meters_per_second_t newDeadband) &&
771 {
772 this->Deadband = std::move(newDeadband);
773 return std::move(*this);
774 }
775
776 /**
777 * \brief Modifies the RotationalDeadband parameter and returns itself.
778 *
779 * The rotational deadband of the request.
780 *
781 * \param newRotationalDeadband Parameter to modify
782 * \returns this object
783 */
784 RobotCentric &WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &
785 {
786 this->RotationalDeadband = std::move(newRotationalDeadband);
787 return *this;
788 }
789 /**
790 * \brief Modifies the RotationalDeadband parameter and returns itself.
791 *
792 * The rotational deadband of the request.
793 *
794 * \param newRotationalDeadband Parameter to modify
795 * \returns this object
796 */
797 RobotCentric &&WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &&
798 {
799 this->RotationalDeadband = std::move(newRotationalDeadband);
800 return std::move(*this);
801 }
802
803 /**
804 * \brief Modifies the CenterOfRotation parameter and returns itself.
805 *
806 * The center of rotation the robot should rotate around. This is (0,0) by
807 * default, which will rotate around the center of the robot.
808 *
809 * \param newCenterOfRotation Parameter to modify
810 * \returns this object
811 */
812 RobotCentric &WithCenterOfRotation(Translation2d newCenterOfRotation) &
813 {
814 this->CenterOfRotation = std::move(newCenterOfRotation);
815 return *this;
816 }
817 /**
818 * \brief Modifies the CenterOfRotation parameter and returns itself.
819 *
820 * The center of rotation the robot should rotate around. This is (0,0) by
821 * default, which will rotate around the center of the robot.
822 *
823 * \param newCenterOfRotation Parameter to modify
824 * \returns this object
825 */
826 RobotCentric &&WithCenterOfRotation(Translation2d newCenterOfRotation) &&
827 {
828 this->CenterOfRotation = std::move(newCenterOfRotation);
829 return std::move(*this);
830 }
831
832 /**
833 * \brief Modifies the DriveRequestType parameter and returns itself.
834 *
835 * The type of control request to use for the drive motor.
836 *
837 * \param newDriveRequestType Parameter to modify
838 * \returns this object
839 */
841 {
842 this->DriveRequestType = std::move(newDriveRequestType);
843 return *this;
844 }
845 /**
846 * \brief Modifies the DriveRequestType parameter and returns itself.
847 *
848 * The type of control request to use for the drive motor.
849 *
850 * \param newDriveRequestType Parameter to modify
851 * \returns this object
852 */
854 {
855 this->DriveRequestType = std::move(newDriveRequestType);
856 return std::move(*this);
857 }
858
859 /**
860 * \brief Modifies the SteerRequestType parameter and returns itself.
861 *
862 * The type of control request to use for the steer motor.
863 *
864 * \param newSteerRequestType Parameter to modify
865 * \returns this object
866 */
868 {
869 this->SteerRequestType = std::move(newSteerRequestType);
870 return *this;
871 }
872 /**
873 * \brief Modifies the SteerRequestType parameter and returns itself.
874 *
875 * The type of control request to use for the steer motor.
876 *
877 * \param newSteerRequestType Parameter to modify
878 * \returns this object
879 */
881 {
882 this->SteerRequestType = std::move(newSteerRequestType);
883 return std::move(*this);
884 }
885
886 /**
887 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
888 *
889 * Whether to desaturate wheel speeds before applying. For more information, see
890 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
891 *
892 * \param newDesaturateWheelSpeeds Parameter to modify
893 * \returns this object
894 */
895 RobotCentric &WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
896 {
897 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
898 return *this;
899 }
900 /**
901 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
902 *
903 * Whether to desaturate wheel speeds before applying. For more information, see
904 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
905 *
906 * \param newDesaturateWheelSpeeds Parameter to modify
907 * \returns this object
908 */
909 RobotCentric &&WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
910 {
911 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
912 return std::move(*this);
913 }
914};
915
916/**
917 * \brief Sets the swerve drive modules to point to a specified direction.
918 */
920public:
921 /**
922 * \brief The direction to point the modules toward. This direction is still
923 * optimized to what the module was previously at.
924 */
925 Rotation2d ModuleDirection{};
926 /**
927 * \brief The type of control request to use for the drive motor.
928 */
930 /**
931 * \brief The type of control request to use for the steer motor.
932 */
934
935 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
936 {
937 auto moduleRequest = impl::SwerveModuleImpl::ModuleRequest{}
940 .WithUpdatePeriod(parameters.updatePeriod);
941 for (size_t i = 0; i < modulesToApply.size(); ++i) {
942 modulesToApply[i]->Apply(moduleRequest.WithState({0_mps, ModuleDirection}));
943 }
944
946 }
947
948 /**
949 * \brief Modifies the ModuleDirection parameter and returns itself.
950 *
951 * The direction to point the modules toward. This direction is still optimized
952 * to what the module was previously at.
953 *
954 * \param newModuleDirection Parameter to modify
955 * \returns this object
956 */
957 PointWheelsAt &WithModuleDirection(Rotation2d newModuleDirection) &
958 {
959 this->ModuleDirection = std::move(newModuleDirection);
960 return *this;
961 }
962 /**
963 * \brief Modifies the ModuleDirection parameter and returns itself.
964 *
965 * The direction to point the modules toward. This direction is still optimized
966 * to what the module was previously at.
967 *
968 * \param newModuleDirection Parameter to modify
969 * \returns this object
970 */
971 PointWheelsAt &&WithModuleDirection(Rotation2d newModuleDirection) &&
972 {
973 this->ModuleDirection = std::move(newModuleDirection);
974 return std::move(*this);
975 }
976
977 /**
978 * \brief Modifies the DriveRequestType parameter and returns itself.
979 *
980 * The type of control request to use for the drive motor.
981 *
982 * \param newDriveRequestType Parameter to modify
983 * \returns this object
984 */
986 {
987 this->DriveRequestType = std::move(newDriveRequestType);
988 return *this;
989 }
990 /**
991 * \brief Modifies the DriveRequestType parameter and returns itself.
992 *
993 * The type of control request to use for the drive motor.
994 *
995 * \param newDriveRequestType Parameter to modify
996 * \returns this object
997 */
999 {
1000 this->DriveRequestType = std::move(newDriveRequestType);
1001 return std::move(*this);
1002 }
1003
1004 /**
1005 * \brief Modifies the SteerRequestType parameter and returns itself.
1006 *
1007 * The type of control request to use for the steer motor.
1008 *
1009 * \param newSteerRequestType Parameter to modify
1010 * \returns this object
1011 */
1013 {
1014 this->SteerRequestType = std::move(newSteerRequestType);
1015 return *this;
1016 }
1017 /**
1018 * \brief Modifies the SteerRequestType parameter and returns itself.
1019 *
1020 * The type of control request to use for the steer motor.
1021 *
1022 * \param newSteerRequestType Parameter to modify
1023 * \returns this object
1024 */
1026 {
1027 this->SteerRequestType = std::move(newSteerRequestType);
1028 return std::move(*this);
1029 }
1030};
1031
1032/**
1033 * \brief Accepts a generic robot-centric ChassisSpeeds to apply to the drivetrain.
1034 * This request is optimized for autonomous or profiled control, which typically
1035 * directly provides ChassisSpeeds and optionally wheel force feedforwards.
1036 *
1037 * Unlike the field-centric requests, this request does not automatically
1038 * discretize the provided ChassisSpeeds.
1039 */
1041public:
1042 /**
1043 * \brief The robot-centric chassis speeds to apply to the drivetrain.
1044 * Users must manually discretize these speeds if appropriate.
1045 */
1046 ChassisSpeeds Speeds{};
1047 /**
1048 * \brief Robot-centric wheel force feedforwards to apply in the
1049 * X direction. X is defined as forward according to WPILib
1050 * convention, so this determines the forward forces to apply.
1051 *
1052 * These forces should include friction applied to the ground.
1053 *
1054 * The order of the forces should match the order of the modules
1055 * returned from SwerveDrivetrain.
1056 */
1057 std::vector<units::newton_t> WheelForceFeedforwardsX;
1058 /**
1059 * \brief Robot-centric wheel force feedforwards to apply in the
1060 * Y direction. Y is defined as to the left according to WPILib
1061 * convention, so this determines the forces to apply to the left.
1062 *
1063 * These forces should include friction applied to the ground.
1064 *
1065 * The order of the forces should match the order of the modules
1066 * returned from SwerveDrivetrain.
1067 */
1068 std::vector<units::newton_t> WheelForceFeedforwardsY;
1069 /**
1070 * \brief The center of rotation to rotate around.
1071 */
1072 Translation2d CenterOfRotation{};
1073 /**
1074 * \brief The type of control request to use for the drive motor.
1075 */
1077 /**
1078 * \brief The type of control request to use for the steer motor.
1079 */
1081 /**
1082 * \brief Whether to desaturate wheel speeds before applying.
1083 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1084 */
1086
1087 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
1088 {
1089 auto states = parameters.kinematics->ToSwerveModuleStates(Speeds, CenterOfRotation);
1090 if (DesaturateWheelSpeeds && parameters.kMaxSpeed > 0_mps) {
1092 }
1093
1094 auto moduleRequest = impl::SwerveModuleImpl::ModuleRequest{}
1097 .WithUpdatePeriod(parameters.updatePeriod);
1098 for (size_t i = 0; i < modulesToApply.size(); ++i) {
1099 if (i < WheelForceFeedforwardsX.size() && i < WheelForceFeedforwardsY.size()) {
1100 moduleRequest.WithWheelForceFeedforwardX(WheelForceFeedforwardsX[i])
1101 .WithWheelForceFeedforwardY(WheelForceFeedforwardsY[i]);
1102 }
1103 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
1104 }
1105
1107 }
1108
1109 /**
1110 * \brief Modifies the Speeds parameter and returns itself.
1111 *
1112 * The robot-centric chassis speeds to apply to the drivetrain.
1113 * Users must manually discretize these speeds if appropriate.
1114 *
1115 * \param newSpeeds Parameter to modify
1116 * \returns this object
1117 */
1118 ApplyRobotSpeeds &WithSpeeds(ChassisSpeeds newSpeeds) &
1119 {
1120 this->Speeds = std::move(newSpeeds);
1121 return *this;
1122 }
1123 /**
1124 * \brief Modifies the Speeds parameter and returns itself.
1125 *
1126 * The robot-centric chassis speeds to apply to the drivetrain.
1127 *
1128 * \param newSpeeds Parameter to modify
1129 * \returns this object
1130 */
1131 ApplyRobotSpeeds &&WithSpeeds(ChassisSpeeds newSpeeds) &&
1132 {
1133 this->Speeds = std::move(newSpeeds);
1134 return std::move(*this);
1135 }
1136
1137 /**
1138 * \brief Modifies the WheelForceFeedforwardsX parameter and returns itself.
1139 *
1140 * Robot-centric wheel force feedforwards to apply in the
1141 * X direction. X is defined as forward according to WPILib
1142 * convention, so this determines the forward forces to apply.
1143 *
1144 * These forces should include friction applied to the ground.
1145 *
1146 * The order of the forces should match the order of the modules
1147 * returned from SwerveDrivetrain.
1148 *
1149 * \param newWheelForceFeedforwardsX Parameter to modify
1150 * \returns this object
1151 */
1152 ApplyRobotSpeeds &WithWheelForceFeedforwardsX(std::vector<units::newton_t> newWheelForceFeedforwardsX) &
1153 {
1154 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1155 return *this;
1156 }
1157 /**
1158 * \brief Modifies the WheelForceFeedforwardsX parameter and returns itself.
1159 *
1160 * Robot-centric wheel force feedforwards to apply in the
1161 * X direction. X is defined as forward according to WPILib
1162 * convention, so this determines the forward forces to apply.
1163 *
1164 * These forces should include friction applied to the ground.
1165 *
1166 * The order of the forces should match the order of the modules
1167 * returned from SwerveDrivetrain.
1168 *
1169 * \param newWheelForceFeedforwardsX Parameter to modify
1170 * \returns this object
1171 */
1172 ApplyRobotSpeeds &&WithWheelForceFeedforwardsX(std::vector<units::newton_t> newWheelForceFeedforwardsX) &&
1173 {
1174 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1175 return std::move(*this);
1176 }
1177
1178 /**
1179 * \brief Modifies the WheelForceFeedforwardsY parameter and returns itself.
1180 *
1181 * Robot-centric wheel force feedforwards to apply in the
1182 * Y direction. Y is defined as to the left according to WPILib
1183 * convention, so this determines the forces to apply to the left.
1184 *
1185 * These forces should include friction applied to the ground.
1186 *
1187 * The order of the forces should match the order of the modules
1188 * returned from SwerveDrivetrain.
1189 *
1190 * \param newWheelForceFeedforwardsY Parameter to modify
1191 * \returns this object
1192 */
1193 ApplyRobotSpeeds &WithWheelForceFeedforwardsY(std::vector<units::newton_t> newWheelForceFeedforwardsY) &
1194 {
1195 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1196 return *this;
1197 }
1198 /**
1199 * \brief Modifies the WheelForceFeedforwardsY parameter and returns itself.
1200 *
1201 * Robot-centric wheel force feedforwards to apply in the
1202 * Y direction. Y is defined as to the left according to WPILib
1203 * convention, so this determines the forces to apply to the left.
1204 *
1205 * These forces should include friction applied to the ground.
1206 *
1207 * The order of the forces should match the order of the modules
1208 * returned from SwerveDrivetrain.
1209 *
1210 * \param newWheelForceFeedforwardsY Parameter to modify
1211 * \returns this object
1212 */
1213 ApplyRobotSpeeds &&WithWheelForceFeedforwardsY(std::vector<units::newton_t> newWheelForceFeedforwardsY) &&
1214 {
1215 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1216 return std::move(*this);
1217 }
1218
1219 /**
1220 * \brief Modifies the CenterOfRotation parameter and returns itself.
1221 *
1222 * The center of rotation the robot should rotate around. This is (0,0) by
1223 * default, which will rotate around the center of the robot.
1224 *
1225 * \param newCenterOfRotation Parameter to modify
1226 * \return this object
1227 */
1228 ApplyRobotSpeeds &WithCenterOfRotation(Translation2d newCenterOfRotation) &
1229 {
1230 this->CenterOfRotation = std::move(newCenterOfRotation);
1231 return *this;
1232 }
1233 /**
1234 * \brief Modifies the CenterOfRotation parameter and returns itself.
1235 *
1236 * The center of rotation the robot should rotate around. This is (0,0) by
1237 * default, which will rotate around the center of the robot.
1238 *
1239 * \param newCenterOfRotation Parameter to modify
1240 * \return this object
1241 */
1242 ApplyRobotSpeeds &&WithCenterOfRotation(Translation2d newCenterOfRotation) &&
1243 {
1244 this->CenterOfRotation = std::move(newCenterOfRotation);
1245 return std::move(*this);
1246 }
1247
1248 /**
1249 * \brief Modifies the DriveRequestType parameter and returns itself.
1250 *
1251 * The type of control request to use for the drive motor.
1252 *
1253 * \param newDriveRequestType Parameter to modify
1254 * \returns this object
1255 */
1257 {
1258 this->DriveRequestType = std::move(newDriveRequestType);
1259 return *this;
1260 }
1261 /**
1262 * \brief Modifies the DriveRequestType parameter and returns itself.
1263 *
1264 * The type of control request to use for the drive motor.
1265 *
1266 * \param newDriveRequestType Parameter to modify
1267 * \returns this object
1268 */
1270 {
1271 this->DriveRequestType = std::move(newDriveRequestType);
1272 return std::move(*this);
1273 }
1274
1275 /**
1276 * \brief Modifies the SteerRequestType parameter and returns itself.
1277 *
1278 * The type of control request to use for the steer motor.
1279 *
1280 * \param newSteerRequestType Parameter to modify
1281 * \returns this object
1282 */
1284 {
1285 this->SteerRequestType = std::move(newSteerRequestType);
1286 return *this;
1287 }
1288 /**
1289 * \brief Modifies the SteerRequestType parameter and returns itself.
1290 *
1291 * The type of control request to use for the steer motor.
1292 *
1293 * \param newSteerRequestType Parameter to modify
1294 * \returns this object
1295 */
1297 {
1298 this->SteerRequestType = std::move(newSteerRequestType);
1299 return std::move(*this);
1300 }
1301
1302 /**
1303 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
1304 *
1305 * Whether to desaturate wheel speeds before applying. For more information, see
1306 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1307 *
1308 * \param newDesaturateWheelSpeeds Parameter to modify
1309 * \returns this object
1310 */
1311 ApplyRobotSpeeds &WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
1312 {
1313 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1314 return *this;
1315 }
1316 /**
1317 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
1318 *
1319 * Whether to desaturate wheel speeds before applying. For more information, see
1320 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1321 *
1322 * \param newDesaturateWheelSpeeds Parameter to modify
1323 * \returns this object
1324 */
1325 ApplyRobotSpeeds &&WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
1326 {
1327 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1328 return std::move(*this);
1329 }
1330};
1331
1332/**
1333 * \brief Accepts a generic field-centric ChassisSpeeds to apply to the drivetrain.
1334 * This request is optimized for autonomous or profiled control, which typically
1335 * directly provides ChassisSpeeds and optionally wheel force feedforwards.
1336 */
1338public:
1339 /**
1340 * \brief The field-centric chassis speeds to apply to the drivetrain.
1341 */
1342 ChassisSpeeds Speeds{};
1343 /**
1344 * \brief Field-centric wheel force feedforwards to apply in the
1345 * X direction. X is defined as forward according to WPILib
1346 * convention, so this determines the forward forces to apply.
1347 *
1348 * These forces should include friction applied to the ground.
1349 *
1350 * The order of the forces should match the order of the modules
1351 * returned from SwerveDrivetrain.
1352 */
1353 std::vector<units::newton_t> WheelForceFeedforwardsX;
1354 /**
1355 * \brief Field-centric wheel force feedforwards to apply in the
1356 * Y direction. Y is defined as to the left according to WPILib
1357 * convention, so this determines the forces to apply to the left.
1358 *
1359 * These forces should include friction applied to the ground.
1360 *
1361 * The order of the forces should match the order of the modules
1362 * returned from SwerveDrivetrain.
1363 */
1364 std::vector<units::newton_t> WheelForceFeedforwardsY;
1365 /**
1366 * \brief The center of rotation to rotate around.
1367 */
1368 Translation2d CenterOfRotation{};
1369 /**
1370 * \brief The type of control request to use for the drive motor.
1371 */
1373 /**
1374 * \brief The type of control request to use for the steer motor.
1375 */
1377 /**
1378 * \brief Whether to desaturate wheel speeds before applying.
1379 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1380 */
1382
1383 /**
1384 * \brief The perspective to use when determining which direction is forward.
1385 */
1387
1388 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
1389 {
1390 auto fieldSpeeds = Speeds;
1392 /* If we're operator perspective, modify the X/Y translation by the angle */
1393 Translation2d tmp{Speeds.vx * 1_s, Speeds.vy * 1_s};
1394 tmp = tmp.RotateBy(parameters.operatorForwardDirection);
1395 fieldSpeeds.vx = tmp.X() / 1_s;
1396 fieldSpeeds.vy = tmp.Y() / 1_s;
1397 }
1398
1399 auto const robotSpeeds = ChassisSpeeds::Discretize(
1400 ChassisSpeeds::FromFieldRelativeSpeeds(
1401 fieldSpeeds, parameters.currentPose.Rotation()
1402 ),
1403 parameters.updatePeriod
1404 );
1405
1406 auto states = parameters.kinematics->ToSwerveModuleStates(robotSpeeds, CenterOfRotation);
1407 if (DesaturateWheelSpeeds && parameters.kMaxSpeed > 0_mps) {
1409 }
1410
1411 auto moduleRequest = impl::SwerveModuleImpl::ModuleRequest{}
1414 .WithUpdatePeriod(parameters.updatePeriod);
1415
1416 for (size_t i = 0; i < modulesToApply.size(); ++i) {
1417 if (i < WheelForceFeedforwardsX.size() && i < WheelForceFeedforwardsY.size()) {
1418 auto wheelForceFeedforwardX = WheelForceFeedforwardsX[i];
1419 auto wheelForceFeedforwardY = WheelForceFeedforwardsY[i];
1420
1421 Translation2d tmp{wheelForceFeedforwardX * 1_m/1_N, wheelForceFeedforwardY * 1_m/1_N};
1423 /* If we're operator perspective, modify the X/Y forces by the angle */
1424 tmp = tmp.RotateBy(parameters.operatorForwardDirection);
1425 }
1426 /* Convert to robot-centric forces */
1427 tmp = tmp.RotateBy(-parameters.currentPose.Rotation());
1428
1429 wheelForceFeedforwardX = tmp.X() * 1_N/1_m;
1430 wheelForceFeedforwardY = tmp.Y() * 1_N/1_m;
1431
1432 moduleRequest.WithWheelForceFeedforwardX(wheelForceFeedforwardX)
1433 .WithWheelForceFeedforwardY(wheelForceFeedforwardY);
1434 }
1435
1436 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
1437 }
1438
1440 }
1441
1442 /**
1443 * \brief Modifies the Speeds parameter and returns itself.
1444 *
1445 * The field-centric chassis speeds to apply to the drivetrain.
1446 *
1447 * \param newSpeeds Parameter to modify
1448 * \returns this object
1449 */
1450 ApplyFieldSpeeds &WithSpeeds(ChassisSpeeds newSpeeds) &
1451 {
1452 this->Speeds = std::move(newSpeeds);
1453 return *this;
1454 }
1455 /**
1456 * \brief Modifies the Speeds parameter and returns itself.
1457 *
1458 * The field-centric chassis speeds to apply to the drivetrain.
1459 *
1460 * \param newSpeeds Parameter to modify
1461 * \returns this object
1462 */
1463 ApplyFieldSpeeds &&WithSpeeds(ChassisSpeeds newSpeeds) &&
1464 {
1465 this->Speeds = std::move(newSpeeds);
1466 return std::move(*this);
1467 }
1468
1469 /**
1470 * \brief Modifies the WheelForceFeedforwardsX parameter and returns itself.
1471 *
1472 * Field-centric wheel force feedforwards to apply in the
1473 * X direction. X is defined as forward according to WPILib
1474 * convention, so this determines the forward forces to apply.
1475 *
1476 * These forces should include friction applied to the ground.
1477 *
1478 * The order of the forces should match the order of the modules
1479 * returned from SwerveDrivetrain.
1480 *
1481 * \param newWheelForceFeedforwardsX Parameter to modify
1482 * \returns this object
1483 */
1484 ApplyFieldSpeeds &WithWheelForceFeedforwardsX(std::vector<units::newton_t> newWheelForceFeedforwardsX) &
1485 {
1486 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1487 return *this;
1488 }
1489 /**
1490 * \brief Modifies the WheelForceFeedforwardsX parameter and returns itself.
1491 *
1492 * Field-centric wheel force feedforwards to apply in the
1493 * X direction. X is defined as forward according to WPILib
1494 * convention, so this determines the forward forces to apply.
1495 *
1496 * These forces should include friction applied to the ground.
1497 *
1498 * The order of the forces should match the order of the modules
1499 * returned from SwerveDrivetrain.
1500 *
1501 * \param newWheelForceFeedforwardsX Parameter to modify
1502 * \returns this object
1503 */
1504 ApplyFieldSpeeds &&WithWheelForceFeedforwardsX(std::vector<units::newton_t> newWheelForceFeedforwardsX) &&
1505 {
1506 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1507 return std::move(*this);
1508 }
1509
1510 /**
1511 * \brief Modifies the WheelForceFeedforwardsY parameter and returns itself.
1512 *
1513 * Field-centric wheel force feedforwards to apply in the
1514 * Y direction. Y is defined as to the left according to WPILib
1515 * convention, so this determines the forces to apply to the left.
1516 *
1517 * These forces should include friction applied to the ground.
1518 *
1519 * The order of the forces should match the order of the modules
1520 * returned from SwerveDrivetrain.
1521 *
1522 * \param newWheelForceFeedforwardsY Parameter to modify
1523 * \returns this object
1524 */
1525 ApplyFieldSpeeds &WithWheelForceFeedforwardsY(std::vector<units::newton_t> newWheelForceFeedforwardsY) &
1526 {
1527 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1528 return *this;
1529 }
1530 /**
1531 * \brief Modifies the WheelForceFeedforwardsY parameter and returns itself.
1532 *
1533 * Field-centric wheel force feedforwards to apply in the
1534 * Y direction. Y is defined as to the left according to WPILib
1535 * convention, so this determines the forces to apply to the left.
1536 *
1537 * These forces should include friction applied to the ground.
1538 *
1539 * The order of the forces should match the order of the modules
1540 * returned from SwerveDrivetrain.
1541 *
1542 * \param newWheelForceFeedforwardsY Parameter to modify
1543 * \returns this object
1544 */
1545 ApplyFieldSpeeds &&WithWheelForceFeedforwardsY(std::vector<units::newton_t> newWheelForceFeedforwardsY) &&
1546 {
1547 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1548 return std::move(*this);
1549 }
1550
1551 /**
1552 * \brief Modifies the CenterOfRotation parameter and returns itself.
1553 *
1554 * The center of rotation the robot should rotate around. This is (0,0) by
1555 * default, which will rotate around the center of the robot.
1556 *
1557 * \param newCenterOfRotation Parameter to modify
1558 * \return this object
1559 */
1560 ApplyFieldSpeeds &WithCenterOfRotation(Translation2d newCenterOfRotation) &
1561 {
1562 this->CenterOfRotation = std::move(newCenterOfRotation);
1563 return *this;
1564 }
1565 /**
1566 * \brief Modifies the CenterOfRotation parameter and returns itself.
1567 *
1568 * The center of rotation the robot should rotate around. This is (0,0) by
1569 * default, which will rotate around the center of the robot.
1570 *
1571 * \param newCenterOfRotation Parameter to modify
1572 * \return this object
1573 */
1574 ApplyFieldSpeeds &&WithCenterOfRotation(Translation2d newCenterOfRotation) &&
1575 {
1576 this->CenterOfRotation = std::move(newCenterOfRotation);
1577 return std::move(*this);
1578 }
1579
1580 /**
1581 * \brief Modifies the DriveRequestType parameter and returns itself.
1582 *
1583 * The type of control request to use for the drive motor.
1584 *
1585 * \param newDriveRequestType Parameter to modify
1586 * \returns this object
1587 */
1589 {
1590 this->DriveRequestType = std::move(newDriveRequestType);
1591 return *this;
1592 }
1593 /**
1594 * \brief Modifies the DriveRequestType parameter and returns itself.
1595 *
1596 * The type of control request to use for the drive motor.
1597 *
1598 * \param newDriveRequestType Parameter to modify
1599 * \returns this object
1600 */
1602 {
1603 this->DriveRequestType = std::move(newDriveRequestType);
1604 return std::move(*this);
1605 }
1606
1607 /**
1608 * \brief Modifies the SteerRequestType parameter and returns itself.
1609 *
1610 * The type of control request to use for the steer motor.
1611 *
1612 * \param newSteerRequestType Parameter to modify
1613 * \returns this object
1614 */
1616 {
1617 this->SteerRequestType = std::move(newSteerRequestType);
1618 return *this;
1619 }
1620 /**
1621 * \brief Modifies the SteerRequestType parameter and returns itself.
1622 *
1623 * The type of control request to use for the steer motor.
1624 *
1625 * \param newSteerRequestType Parameter to modify
1626 * \returns this object
1627 */
1629 {
1630 this->SteerRequestType = std::move(newSteerRequestType);
1631 return std::move(*this);
1632 }
1633
1634 /**
1635 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
1636 *
1637 * Whether to desaturate wheel speeds before applying. For more information, see
1638 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1639 *
1640 * \param newDesaturateWheelSpeeds Parameter to modify
1641 * \returns this object
1642 */
1643 ApplyFieldSpeeds &WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
1644 {
1645 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1646 return *this;
1647 }
1648 /**
1649 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
1650 *
1651 * Whether to desaturate wheel speeds before applying. For more information, see
1652 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1653 *
1654 * \param newDesaturateWheelSpeeds Parameter to modify
1655 * \returns this object
1656 */
1657 ApplyFieldSpeeds &&WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
1658 {
1659 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1660 return std::move(*this);
1661 }
1662
1663 /**
1664 * \brief Modifies the ForwardPerspective parameter and returns itself.
1665 *
1666 * The perspective to use when determining which direction is forward.
1667 *
1668 * \param newForwardPerspective Parameter to modify
1669 * \returns this object
1670 */
1672 {
1673 this->ForwardPerspective = std::move(newForwardPerspective);
1674 return *this;
1675 }
1676 /**
1677 * \brief Modifies the ForwardPerspective parameter and returns itself.
1678 *
1679 * The perspective to use when determining which direction is forward.
1680 *
1681 * \param newForwardPerspective Parameter to modify
1682 * \returns this object
1683 */
1685 {
1686 this->ForwardPerspective = std::move(newForwardPerspective);
1687 return std::move(*this);
1688 }
1689};
1690
1691/**
1692 * \brief Drives the swerve drivetrain in a field-centric manner, maintaining a
1693 * specified heading angle to ensure the robot is facing the desired direction
1694 *
1695 * When users use this request, they specify the direction the robot should
1696 * travel oriented against the field, and the direction the robot should be facing.
1697 *
1698 * An example scenario is that the robot is oriented to the east, the VelocityX
1699 * is +5 m/s, VelocityY is 0 m/s, and TargetDirection is 180 degrees.
1700 * In this scenario, the robot would drive northward at 5 m/s and turn clockwise
1701 * to a target of 180 degrees.
1702 *
1703 * This control request is especially useful for autonomous control, where the
1704 * robot should be facing a changing direction throughout the motion.
1705 */
1707public:
1708 /**
1709 * \brief The velocity in the X direction. X is defined as forward according
1710 * to WPILib convention, so this determines how fast to travel forward.
1711 */
1712 units::meters_per_second_t VelocityX = 0_mps;
1713 /**
1714 * \brief The velocity in the Y direction. Y is defined as to the left
1715 * according to WPILib convention, so this determines how fast to travel to
1716 * the left.
1717 */
1718 units::meters_per_second_t VelocityY = 0_mps;
1719 /**
1720 * \brief The desired direction to face.
1721 * 0 Degrees is defined as in the direction of the X axis.
1722 * As a result, a TargetDirection of 90 degrees will point along
1723 * the Y axis, or to the left.
1724 */
1725 Rotation2d TargetDirection{};
1726 /**
1727 * \brief The rotational rate feedforward to add to the output of the heading
1728 * controller, in radians per second. When using a motion profile for the
1729 * target direction, this can be set to the current velocity reference of
1730 * the profile.
1731 */
1732 units::radians_per_second_t TargetRateFeedforward = 0_rad_per_s;
1733
1734 /**
1735 * \brief The allowable deadband of the request.
1736 */
1737 units::meters_per_second_t Deadband = 0_mps;
1738 /**
1739 * \brief The rotational deadband of the request.
1740 */
1741 units::radians_per_second_t RotationalDeadband = 0_rad_per_s;
1742 /**
1743 * \brief The maximum absolute rotational rate to allow.
1744 * Setting this to 0 results in no cap to rotational rate.
1745 */
1746 units::radians_per_second_t MaxAbsRotationalRate = 0_rad_per_s;
1747 /**
1748 * \brief The center of rotation the robot should rotate around. This is
1749 * (0,0) by default, which will rotate around the center of the robot.
1750 */
1751 Translation2d CenterOfRotation{};
1752
1753 /**
1754 * \brief The type of control request to use for the drive motor.
1755 */
1757 /**
1758 * \brief The type of control request to use for the steer motor.
1759 */
1761 /**
1762 * \brief Whether to desaturate wheel speeds before applying.
1763 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1764 */
1766
1767 /**
1768 * \brief The perspective to use when determining which direction is forward.
1769 */
1771 /**
1772 * \brief The perspective to use when determining which direction is forward
1773 * for the #TargetDirection. This allows for the heading control to use a different
1774 * perspective from the translation control.
1775 */
1777
1778 /**
1779 * \brief The PID controller used to maintain the desired heading.
1780 * Users can specify the PID gains to change how aggressively to maintain
1781 * heading.
1782 *
1783 * This PID controller operates on heading radians and outputs a target
1784 * rotational rate in radians per second. Note that continuous input should
1785 * be enabled on the range [-pi, pi].
1786 */
1788
1790 {
1791 HeadingController.EnableContinuousInput(-units::constants::detail::PI_VAL, units::constants::detail::PI_VAL);
1792 }
1793
1794 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
1795 {
1796 Rotation2d angleToFace = TargetDirection;
1797 if (
1800 ) {
1801 /* If we're operator perspective, rotate the direction we want to face by the angle */
1802 angleToFace = angleToFace.RotateBy(parameters.operatorForwardDirection);
1803 }
1804
1805 units::radians_per_second_t toApplyOmega = TargetRateFeedforward +
1806 units::radians_per_second_t{HeadingController.Calculate(
1807 parameters.currentPose.Rotation().Radians().value(),
1808 angleToFace.Radians().value(),
1809 parameters.timestamp
1810 )};
1811 if (MaxAbsRotationalRate > 0_rad_per_s) {
1812 if (toApplyOmega > MaxAbsRotationalRate) {
1813 toApplyOmega = MaxAbsRotationalRate;
1814 } else if (toApplyOmega < -MaxAbsRotationalRate) {
1815 toApplyOmega = -MaxAbsRotationalRate;
1816 }
1817 }
1818
1819 return FieldCentric{}
1822 .WithRotationalRate(toApplyOmega)
1830 .Apply(parameters, modulesToApply);
1831 }
1832
1833 /**
1834 * \brief Modifies the PID gains of the HeadingController parameter and returns itself.
1835 *
1836 * Sets the proportional, integral, and differential coefficients used to maintain
1837 * the desired heading. Users can specify the PID gains to change how aggressively to
1838 * maintain heading.
1839 *
1840 * This PID controller operates on heading radians and outputs a target
1841 * rotational rate in radians per second.
1842 *
1843 * \param kP The proportional coefficient; must be >= 0
1844 * \param kI The integral coefficient; must be >= 0
1845 * \param kD The differential coefficient; must be >= 0
1846 * \returns this object
1847 */
1848 FieldCentricFacingAngle &WithHeadingPID(double kP, double kI, double kD)
1849 {
1850 this->HeadingController.SetPID(kP, kI, kD);
1851 return *this;
1852 }
1853
1854 /**
1855 * \brief Modifies the VelocityX parameter and returns itself.
1856 *
1857 * The velocity in the X direction. X is defined as forward according to
1858 * WPILib convention, so this determines how fast to travel forward.
1859 *
1860 * \param newVelocityX Parameter to modify
1861 * \returns this object
1862 */
1863 FieldCentricFacingAngle &WithVelocityX(units::meters_per_second_t newVelocityX)
1864 {
1865 this->VelocityX = std::move(newVelocityX);
1866 return *this;
1867 }
1868
1869 /**
1870 * \brief Modifies the VelocityY parameter and returns itself.
1871 *
1872 * The velocity in the Y direction. Y is defined as to the left according
1873 * to WPILib convention, so this determines how fast to travel to the
1874 * left.
1875 *
1876 * \param newVelocityY Parameter to modify
1877 * \returns this object
1878 */
1879 FieldCentricFacingAngle &WithVelocityY(units::meters_per_second_t newVelocityY)
1880 {
1881 this->VelocityY = std::move(newVelocityY);
1882 return *this;
1883 }
1884
1885 /**
1886 * \brief Modifies the VelocityY parameter and returns itself.
1887 *
1888 * The desired direction to face. 0 Degrees is defined as in the direction of
1889 * the X axis. As a result, a TargetDirection of 90 degrees will point along
1890 * the Y axis, or to the left.
1891 *
1892 * \param newTargetDirection Parameter to modify
1893 * \returns this object
1894 */
1895 FieldCentricFacingAngle &WithTargetDirection(Rotation2d newTargetDirection)
1896 {
1897 this->TargetDirection = std::move(newTargetDirection);
1898 return *this;
1899 }
1900
1901 /**
1902 * \brief Modifies the VelocityY parameter and returns itself.
1903 *
1904 * The rotational rate feedforward to add to the output of the heading
1905 * controller, in radians per second. When using a motion profile for the
1906 * target direction, this can be set to the current velocity reference of
1907 * the profile.
1908 *
1909 * \param newTargetRateFeedforward Parameter to modify
1910 * \returns this object
1911 */
1912 FieldCentricFacingAngle &WithTargetRateFeedforward(units::radians_per_second_t newTargetRateFeedforward)
1913 {
1914 this->TargetRateFeedforward = std::move(newTargetRateFeedforward);
1915 return *this;
1916 }
1917
1918 /**
1919 * \brief Modifies the Deadband parameter and returns itself.
1920 *
1921 * The allowable deadband of the request.
1922 *
1923 * \param newDeadband Parameter to modify
1924 * \returns this object
1925 */
1926 FieldCentricFacingAngle &WithDeadband(units::meters_per_second_t newDeadband)
1927 {
1928 this->Deadband = std::move(newDeadband);
1929 return *this;
1930 }
1931
1932 /**
1933 * \brief Modifies the RotationalDeadband parameter and returns itself.
1934 *
1935 * The rotational deadband of the request.
1936 *
1937 * \param newRotationalDeadband Parameter to modify
1938 * \returns this object
1939 */
1940 FieldCentricFacingAngle &WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband)
1941 {
1942 this->RotationalDeadband = std::move(newRotationalDeadband);
1943 return *this;
1944 }
1945
1946 /**
1947 * \brief Modifies the MaxAbsRotationalRate parameter and returns itself.
1948 *
1949 * The maximum absolute rotational rate to allow.
1950 * Setting this to 0 results in no cap to rotational rate.
1951 *
1952 * \param newMaxAbsRotationalRate Parameter to modify
1953 * \returns this object
1954 */
1955 FieldCentricFacingAngle &WithMaxAbsRotationalRate(units::radians_per_second_t newMaxAbsRotationalRate)
1956 {
1957 this->MaxAbsRotationalRate = std::move(newMaxAbsRotationalRate);
1958 return *this;
1959 }
1960
1961 /**
1962 * \brief Modifies the CenterOfRotation parameter and returns itself.
1963 *
1964 * The center of rotation the robot should rotate around. This is (0,0) by
1965 * default, which will rotate around the center of the robot.
1966 *
1967 * \param newCenterOfRotation Parameter to modify
1968 * \returns this object
1969 */
1970 FieldCentricFacingAngle &WithCenterOfRotation(Translation2d newCenterOfRotation)
1971 {
1972 this->CenterOfRotation = std::move(newCenterOfRotation);
1973 return *this;
1974 }
1975
1976 /**
1977 * \brief Modifies the DriveRequestType parameter and returns itself.
1978 *
1979 * The type of control request to use for the drive motor.
1980 *
1981 * \param newDriveRequestType Parameter to modify
1982 * \returns this object
1983 */
1985 {
1986 this->DriveRequestType = std::move(newDriveRequestType);
1987 return *this;
1988 }
1989
1990 /**
1991 * \brief Modifies the SteerRequestType parameter and returns itself.
1992 *
1993 * The type of control request to use for the steer motor.
1994 *
1995 * \param newSteerRequestType Parameter to modify
1996 * \returns this object
1997 */
1999 {
2000 this->SteerRequestType = std::move(newSteerRequestType);
2001 return *this;
2002 }
2003
2004 /**
2005 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
2006 *
2007 * Whether to desaturate wheel speeds before applying. For more information, see
2008 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
2009 *
2010 * \param newDesaturateWheelSpeeds Parameter to modify
2011 * \returns this object
2012 */
2014 {
2015 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
2016 return *this;
2017 }
2018
2019 /**
2020 * \brief Modifies the ForwardPerspective parameter and returns itself.
2021 *
2022 * The perspective to use when determining which direction is forward.
2023 *
2024 * \param newForwardPerspective Parameter to modify
2025 * \returns this object
2026 */
2028 {
2029 this->ForwardPerspective = std::move(newForwardPerspective);
2030 return *this;
2031 }
2032
2033 /**
2034 * \brief Modifies the TargetDirectionPerspective parameter and returns itself.
2035 *
2036 * The perspective to use when determining which direction is forward for the
2037 * #TargetDirection. This allows for the rotation control to use a different
2038 * perspective from the translation control.
2039 *
2040 * \param newTargetDirectionPerspective Parameter to modify
2041 * \returns this object
2042 */
2044 {
2045 this->TargetDirectionPerspective = std::move(newTargetDirectionPerspective);
2046 return *this;
2047 }
2048};
2049
2050/**
2051 * \brief Drives the swerve drivetrain in a robot-centric manner, maintaining a
2052 * specified heading angle to ensure the robot is facing the desired direction
2053 *
2054 * When users use this request, they specify the direction the robot should
2055 * travel oriented against the robot itself, and the direction the robot should
2056 * be facing relative to the field.
2057 *
2058 * An example scenario is that the robot is oriented to the east, the VelocityX
2059 * is +5 m/s, VelocityY is 0 m/s, and TargetDirection is 180 degrees.
2060 * In this scenario, the robot would drive forward at 5 m/s and turn clockwise
2061 * to a target of 180 degrees.
2062 *
2063 * This control request is especially useful for vision control, where the
2064 * robot should be facing a vision target throughout the motion.
2065 */
2067public:
2068 /**
2069 * \brief The velocity in the X direction. X is defined as forward according
2070 * to WPILib convention, so this determines how fast to travel forward.
2071 */
2072 units::meters_per_second_t VelocityX = 0_mps;
2073 /**
2074 * \brief The velocity in the Y direction. Y is defined as to the left
2075 * according to WPILib convention, so this determines how fast to travel to
2076 * the left.
2077 */
2078 units::meters_per_second_t VelocityY = 0_mps;
2079 /**
2080 * \brief The desired direction to face.
2081 * 0 Degrees is defined as in the direction of the X axis.
2082 * As a result, a TargetDirection of 90 degrees will point along
2083 * the Y axis, or to the left.
2084 */
2085 Rotation2d TargetDirection{};
2086 /**
2087 * \brief The rotational rate feedforward to add to the output of the heading
2088 * controller, in radians per second. When using a motion profile for the
2089 * target direction, this can be set to the current velocity reference of
2090 * the profile.
2091 */
2092 units::radians_per_second_t TargetRateFeedforward = 0_rad_per_s;
2093
2094 /**
2095 * \brief The allowable deadband of the request.
2096 */
2097 units::meters_per_second_t Deadband = 0_mps;
2098 /**
2099 * \brief The rotational deadband of the request.
2100 */
2101 units::radians_per_second_t RotationalDeadband = 0_rad_per_s;
2102 /**
2103 * \brief The maximum absolute rotational rate to allow.
2104 * Setting this to 0 results in no cap to rotational rate.
2105 */
2106 units::radians_per_second_t MaxAbsRotationalRate = 0_rad_per_s;
2107 /**
2108 * \brief The center of rotation the robot should rotate around. This is
2109 * (0,0) by default, which will rotate around the center of the robot.
2110 */
2111 Translation2d CenterOfRotation{};
2112
2113 /**
2114 * \brief The type of control request to use for the drive motor.
2115 */
2117 /**
2118 * \brief The type of control request to use for the steer motor.
2119 */
2121 /**
2122 * \brief Whether to desaturate wheel speeds before applying.
2123 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
2124 */
2126
2127 /**
2128 * \brief The perspective to use when determining which direction is forward
2129 * for the target heading.
2130 */
2132
2133 /**
2134 * \brief The PID controller used to maintain the desired heading.
2135 * Users can specify the PID gains to change how aggressively to maintain
2136 * heading.
2137 *
2138 * This PID controller operates on heading radians and outputs a target
2139 * rotational rate in radians per second. Note that continuous input should
2140 * be enabled on the range [-pi, pi].
2141 */
2143
2145 {
2146 HeadingController.EnableContinuousInput(-units::constants::detail::PI_VAL, units::constants::detail::PI_VAL);
2147 }
2148
2149 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
2150 {
2151 Rotation2d angleToFace = TargetDirection;
2153 /* If we're operator perspective, rotate the direction we want to face by the angle */
2154 angleToFace = angleToFace.RotateBy(parameters.operatorForwardDirection);
2155 }
2156
2157 units::radians_per_second_t toApplyOmega = TargetRateFeedforward +
2158 units::radians_per_second_t{HeadingController.Calculate(
2159 parameters.currentPose.Rotation().Radians().value(),
2160 angleToFace.Radians().value(),
2161 parameters.timestamp
2162 )};
2163 if (MaxAbsRotationalRate > 0_rad_per_s) {
2164 if (toApplyOmega > MaxAbsRotationalRate) {
2165 toApplyOmega = MaxAbsRotationalRate;
2166 } else if (toApplyOmega < -MaxAbsRotationalRate) {
2167 toApplyOmega = -MaxAbsRotationalRate;
2168 }
2169 }
2170
2171 return RobotCentric{}
2174 .WithRotationalRate(toApplyOmega)
2181 .Apply(parameters, modulesToApply);
2182 }
2183
2184 /**
2185 * \brief Modifies the PID gains of the HeadingController parameter and returns itself.
2186 *
2187 * Sets the proportional, integral, and differential coefficients used to maintain
2188 * the desired heading. Users can specify the PID gains to change how aggressively to
2189 * maintain heading.
2190 *
2191 * This PID controller operates on heading radians and outputs a target
2192 * rotational rate in radians per second.
2193 *
2194 * \param kP The proportional coefficient; must be >= 0
2195 * \param kI The integral coefficient; must be >= 0
2196 * \param kD The differential coefficient; must be >= 0
2197 * \returns this object
2198 */
2199 RobotCentricFacingAngle &WithHeadingPID(double kP, double kI, double kD)
2200 {
2201 this->HeadingController.SetPID(kP, kI, kD);
2202 return *this;
2203 }
2204
2205 /**
2206 * \brief Modifies the VelocityX parameter and returns itself.
2207 *
2208 * The velocity in the X direction. X is defined as forward according to
2209 * WPILib convention, so this determines how fast to travel forward.
2210 *
2211 * \param newVelocityX Parameter to modify
2212 * \returns this object
2213 */
2214 RobotCentricFacingAngle &WithVelocityX(units::meters_per_second_t newVelocityX)
2215 {
2216 this->VelocityX = std::move(newVelocityX);
2217 return *this;
2218 }
2219
2220 /**
2221 * \brief Modifies the VelocityY parameter and returns itself.
2222 *
2223 * The velocity in the Y direction. Y is defined as to the left according
2224 * to WPILib convention, so this determines how fast to travel to the
2225 * left.
2226 *
2227 * \param newVelocityY Parameter to modify
2228 * \returns this object
2229 */
2230 RobotCentricFacingAngle &WithVelocityY(units::meters_per_second_t newVelocityY)
2231 {
2232 this->VelocityY = std::move(newVelocityY);
2233 return *this;
2234 }
2235
2236 /**
2237 * \brief Modifies the VelocityY parameter and returns itself.
2238 *
2239 * The desired direction to face. 0 Degrees is defined as in the direction of
2240 * the X axis. As a result, a TargetDirection of 90 degrees will point along
2241 * the Y axis, or to the left.
2242 *
2243 * \param newTargetDirection Parameter to modify
2244 * \returns this object
2245 */
2246 RobotCentricFacingAngle &WithTargetDirection(Rotation2d newTargetDirection)
2247 {
2248 this->TargetDirection = std::move(newTargetDirection);
2249 return *this;
2250 }
2251
2252 /**
2253 * \brief Modifies the VelocityY parameter and returns itself.
2254 *
2255 * The rotational rate feedforward to add to the output of the heading
2256 * controller, in radians per second. When using a motion profile for the
2257 * target direction, this can be set to the current velocity reference of
2258 * the profile.
2259 *
2260 * \param newTargetRateFeedforward Parameter to modify
2261 * \returns this object
2262 */
2263 RobotCentricFacingAngle &WithTargetRateFeedforward(units::radians_per_second_t newTargetRateFeedforward)
2264 {
2265 this->TargetRateFeedforward = std::move(newTargetRateFeedforward);
2266 return *this;
2267 }
2268
2269 /**
2270 * \brief Modifies the Deadband parameter and returns itself.
2271 *
2272 * The allowable deadband of the request.
2273 *
2274 * \param newDeadband Parameter to modify
2275 * \returns this object
2276 */
2277 RobotCentricFacingAngle &WithDeadband(units::meters_per_second_t newDeadband)
2278 {
2279 this->Deadband = std::move(newDeadband);
2280 return *this;
2281 }
2282
2283 /**
2284 * \brief Modifies the RotationalDeadband parameter and returns itself.
2285 *
2286 * The rotational deadband of the request.
2287 *
2288 * \param newRotationalDeadband Parameter to modify
2289 * \returns this object
2290 */
2291 RobotCentricFacingAngle &WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband)
2292 {
2293 this->RotationalDeadband = std::move(newRotationalDeadband);
2294 return *this;
2295 }
2296
2297 /**
2298 * \brief Modifies the MaxAbsRotationalRate parameter and returns itself.
2299 *
2300 * The maximum absolute rotational rate to allow.
2301 * Setting this to 0 results in no cap to rotational rate.
2302 *
2303 * \param newMaxAbsRotationalRate Parameter to modify
2304 * \returns this object
2305 */
2306 RobotCentricFacingAngle &WithMaxAbsRotationalRate(units::radians_per_second_t newMaxAbsRotationalRate)
2307 {
2308 this->MaxAbsRotationalRate = std::move(newMaxAbsRotationalRate);
2309 return *this;
2310 }
2311
2312 /**
2313 * \brief Modifies the CenterOfRotation parameter and returns itself.
2314 *
2315 * The center of rotation the robot should rotate around. This is (0,0) by
2316 * default, which will rotate around the center of the robot.
2317 *
2318 * \param newCenterOfRotation Parameter to modify
2319 * \returns this object
2320 */
2321 RobotCentricFacingAngle &WithCenterOfRotation(Translation2d newCenterOfRotation)
2322 {
2323 this->CenterOfRotation = std::move(newCenterOfRotation);
2324 return *this;
2325 }
2326
2327 /**
2328 * \brief Modifies the DriveRequestType parameter and returns itself.
2329 *
2330 * The type of control request to use for the drive motor.
2331 *
2332 * \param newDriveRequestType Parameter to modify
2333 * \returns this object
2334 */
2336 {
2337 this->DriveRequestType = std::move(newDriveRequestType);
2338 return *this;
2339 }
2340
2341 /**
2342 * \brief Modifies the SteerRequestType parameter and returns itself.
2343 *
2344 * The type of control request to use for the steer motor.
2345 *
2346 * \param newSteerRequestType Parameter to modify
2347 * \returns this object
2348 */
2350 {
2351 this->SteerRequestType = std::move(newSteerRequestType);
2352 return *this;
2353 }
2354
2355 /**
2356 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
2357 *
2358 * Whether to desaturate wheel speeds before applying. For more information, see
2359 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
2360 *
2361 * \param newDesaturateWheelSpeeds Parameter to modify
2362 * \returns this object
2363 */
2365 {
2366 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
2367 return *this;
2368 }
2369
2370 /**
2371 * \brief Modifies the ForwardPerspective parameter and returns itself.
2372 *
2373 * The perspective to use when determining which direction is forward
2374 * for the target heading.
2375 *
2376 * \param newForwardPerspective Parameter to modify
2377 * \returns this object
2378 */
2380 {
2381 this->ForwardPerspective = std::move(newForwardPerspective);
2382 return *this;
2383 }
2384};
2385
2386/**
2387 * \brief SysId-specific SwerveRequest to characterize the translational
2388 * characteristics of a swerve drivetrain.
2389 */
2391public:
2392 /**
2393 * \brief Voltage to apply to drive wheels.
2394 */
2395 units::volt_t VoltsToApply = 0_V;
2396
2397 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
2398 {
2399 for (size_t i = 0; i < modulesToApply.size(); ++i) {
2400 switch (modulesToApply[i]->GetSteerClosedLoopOutputType()) {
2402 modulesToApply[i]->Apply(
2405 );
2406 break;
2408 modulesToApply[i]->Apply(
2411 );
2412 break;
2413 }
2414 }
2416 }
2417
2418 /**
2419 * \brief Sets the voltage to apply to drive wheels.
2420 *
2421 * \param volts Voltage to apply
2422 * \returns this request
2423 */
2424 SysIdSwerveTranslation &WithVolts(units::volt_t volts) &
2425 {
2426 this->VoltsToApply = volts;
2427 return *this;
2428 }
2429 /**
2430 * \brief Sets the voltage to apply to drive wheels.
2431 *
2432 * \param volts Voltage to apply
2433 * \returns this request
2434 */
2435 SysIdSwerveTranslation &&WithVolts(units::volt_t volts) &&
2436 {
2437 this->VoltsToApply = volts;
2438 return std::move(*this);
2439 }
2440};
2441
2442/**
2443 * \brief SysId-specific SwerveRequest to characterize the rotational
2444 * characteristics of a swerve drivetrain. This is useful to
2445 * characterize the heading controller for FieldCentricFacingAngle.
2446 *
2447 * The RotationalRate of this swerve request should be logged.
2448 * When importing the log to SysId, set the "voltage" to
2449 * RotationalRate, "position" to the Pigeon 2 Yaw, and "velocity"
2450 * to the Pigeon 2 AngularVelocityZWorld. Note that the position
2451 * and velocity will both need to be scaled by pi/180.
2452 *
2453 * Alternatively, the MotorVoltage of one of the drive motors can
2454 * be loaded into the SysId "voltage" field, which can be useful
2455 * when determining the MOI of the robot.
2456 */
2458public:
2459 /**
2460 * \brief The angular rate to rotate at, in radians per second.
2461 */
2462 units::radians_per_second_t RotationalRate = 0_rad_per_s;
2463
2464 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
2465 {
2466 for (size_t i = 0; i < modulesToApply.size(); ++i) {
2467 auto const speed = RotationalRate * (parameters.moduleLocations[i].Norm() / 1_rad);
2468 auto const driveVoltage = speed / parameters.kMaxSpeed * 12_V;
2469
2470 auto const angle = parameters.moduleLocations[i].Angle() + Rotation2d{90_deg};
2471
2472 switch (modulesToApply[i]->GetSteerClosedLoopOutputType()) {
2474 modulesToApply[i]->Apply(
2475 controls::VoltageOut{driveVoltage},
2476 controls::PositionVoltage{angle.Radians()}
2477 );
2478 break;
2480 modulesToApply[i]->Apply(
2481 controls::VoltageOut{driveVoltage},
2482 controls::PositionTorqueCurrentFOC{angle.Radians()}
2483 );
2484 break;
2485 }
2486 }
2488 }
2489
2490 /**
2491 * \brief Update the angular rate to rotate at, in radians per second.
2492 *
2493 * \param rotationalRate Angular rate to rotate at
2494 * \returns this request
2495 */
2496 SysIdSwerveRotation &WithRotationalRate(units::radians_per_second_t rotationalRate) &
2497 {
2498 this->RotationalRate = rotationalRate;
2499 return *this;
2500 }
2501 /**
2502 * \brief Update the angular rate to rotate at, in radians per second.
2503 *
2504 * \param rotationalRate Angular rate to rotate at
2505 * \returns this request
2506 */
2507 SysIdSwerveRotation &&WithRotationalRate(units::radians_per_second_t rotationalRate) &&
2508 {
2509 this->RotationalRate = rotationalRate;
2510 return std::move(*this);
2511 }
2512};
2513
2514/**
2515 * \brief SysId-specific SwerveRequest to characterize the steer module
2516 * characteristics of a swerve drivetrain.
2517 */
2519public:
2520 /**
2521 * \brief Voltage to apply to drive wheels.
2522 */
2523 units::volt_t VoltsToApply = 0_V;
2524
2525 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
2526 {
2527 for (size_t i = 0; i < modulesToApply.size(); ++i) {
2528 modulesToApply[i]->Apply(controls::CoastOut{}, controls::VoltageOut{VoltsToApply});
2529 }
2531 }
2532
2533 /**
2534 * \brief Update the voltage to apply to the drive wheels.
2535 *
2536 * \param volts Voltage to apply
2537 * \returns this request
2538 */
2539 SysIdSwerveSteerGains &WithVolts(units::volt_t volts) &
2540 {
2541 this->VoltsToApply = volts;
2542 return *this;
2543 }
2544 /**
2545 * \brief Update the voltage to apply to the drive wheels.
2546 *
2547 * \param volts Voltage to apply
2548 * \returns this request
2549 */
2550 SysIdSwerveSteerGains &&WithVolts(units::volt_t volts) &&
2551 {
2552 this->VoltsToApply = volts;
2553 return std::move(*this);
2554 }
2555};
2556
2557}
2558}
2559}
2560}
Request coast neutral output of actuator.
Definition CoastOut.hpp:21
Requires Phoenix Pro; Request PID to target position with torque current feedforward.
Definition PositionTorqueCurrentFOC.hpp:27
Request PID to target position with voltage feedforward.
Definition PositionVoltage.hpp:26
Request a specified voltage.
Definition VoltageOut.hpp:24
Phoenix-centric PID controller taken from WPI's frc#PIDController class.
Definition PhoenixPIDController.hpp:22
double Calculate(double measurement, double setpoint, units::second_t currentTimestamp)
Returns the next output of the PID controller.
void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
static void DesaturateWheelSpeeds(WheelSpeeds *moduleStates, units::meters_per_second_t attainableMaxSpeed)
Renormalizes the wheel speeds if any individual speed is above the specified maximum.
WheelSpeeds ToSwerveModuleStates(ChassisSpeeds const &chassisSpeeds, Translation2d const &centerOfRotation=Translation2d{})
Performs inverse kinematics to return the module states from a desired chassis velocity.
Accepts a generic field-centric ChassisSpeeds to apply to the drivetrain.
Definition SwerveRequest.hpp:1337
ApplyFieldSpeeds && WithWheelForceFeedforwardsY(std::vector< units::newton_t > newWheelForceFeedforwardsY) &&
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Definition SwerveRequest.hpp:1545
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:1381
ApplyFieldSpeeds && WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &&
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1504
ApplyFieldSpeeds && WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective) &&
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:1684
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward.
Definition SwerveRequest.hpp:1386
ApplyFieldSpeeds & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1588
ApplyFieldSpeeds && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1574
ApplyFieldSpeeds & WithWheelForceFeedforwardsY(std::vector< units::newton_t > newWheelForceFeedforwardsY) &
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Definition SwerveRequest.hpp:1525
ApplyFieldSpeeds & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1643
ChassisSpeeds Speeds
The field-centric chassis speeds to apply to the drivetrain.
Definition SwerveRequest.hpp:1342
ApplyFieldSpeeds & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1615
ApplyFieldSpeeds & WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1484
ApplyFieldSpeeds && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1628
std::vector< units::newton_t > WheelForceFeedforwardsX
Field-centric wheel force feedforwards to apply in the X direction.
Definition SwerveRequest.hpp:1353
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1388
ApplyFieldSpeeds && WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1657
ApplyFieldSpeeds & WithSpeeds(ChassisSpeeds newSpeeds) &
Modifies the Speeds parameter and returns itself.
Definition SwerveRequest.hpp:1450
std::vector< units::newton_t > WheelForceFeedforwardsY
Field-centric wheel force feedforwards to apply in the Y direction.
Definition SwerveRequest.hpp:1364
Translation2d CenterOfRotation
The center of rotation to rotate around.
Definition SwerveRequest.hpp:1368
ApplyFieldSpeeds && WithSpeeds(ChassisSpeeds newSpeeds) &&
Modifies the Speeds parameter and returns itself.
Definition SwerveRequest.hpp:1463
ApplyFieldSpeeds & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1560
ApplyFieldSpeeds && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1601
ApplyFieldSpeeds & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective) &
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:1671
Accepts a generic robot-centric ChassisSpeeds to apply to the drivetrain.
Definition SwerveRequest.hpp:1040
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1087
ApplyRobotSpeeds && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1296
ChassisSpeeds Speeds
The robot-centric chassis speeds to apply to the drivetrain.
Definition SwerveRequest.hpp:1046
std::vector< units::newton_t > WheelForceFeedforwardsY
Robot-centric wheel force feedforwards to apply in the Y direction.
Definition SwerveRequest.hpp:1068
std::vector< units::newton_t > WheelForceFeedforwardsX
Robot-centric wheel force feedforwards to apply in the X direction.
Definition SwerveRequest.hpp:1057
ApplyRobotSpeeds && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1242
ApplyRobotSpeeds & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1256
ApplyRobotSpeeds & WithSpeeds(ChassisSpeeds newSpeeds) &
Modifies the Speeds parameter and returns itself.
Definition SwerveRequest.hpp:1118
ApplyRobotSpeeds & WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1152
ApplyRobotSpeeds && WithSpeeds(ChassisSpeeds newSpeeds) &&
Modifies the Speeds parameter and returns itself.
Definition SwerveRequest.hpp:1131
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:1085
ApplyRobotSpeeds & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1283
ApplyRobotSpeeds & WithWheelForceFeedforwardsY(std::vector< units::newton_t > newWheelForceFeedforwardsY) &
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Definition SwerveRequest.hpp:1193
ApplyRobotSpeeds & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1228
ApplyRobotSpeeds && WithWheelForceFeedforwardsY(std::vector< units::newton_t > newWheelForceFeedforwardsY) &&
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Definition SwerveRequest.hpp:1213
ApplyRobotSpeeds && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1269
Translation2d CenterOfRotation
The center of rotation to rotate around.
Definition SwerveRequest.hpp:1072
ApplyRobotSpeeds && WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &&
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1172
ApplyRobotSpeeds && WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1325
ApplyRobotSpeeds & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1311
Drives the swerve drivetrain in a field-centric manner, maintaining a specified heading angle to ensu...
Definition SwerveRequest.hpp:1706
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:1765
TargetDirectionPerspectiveValue TargetDirectionPerspective
The perspective to use when determining which direction is forward for the TargetDirection.
Definition SwerveRequest.hpp:1776
FieldCentricFacingAngle & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband)
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:1940
FieldCentricFacingAngle & WithMaxAbsRotationalRate(units::radians_per_second_t newMaxAbsRotationalRate)
Modifies the MaxAbsRotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:1955
FieldCentricFacingAngle & WithTargetDirectionPerspective(TargetDirectionPerspectiveValue newTargetDirectionPerspective)
Modifies the TargetDirectionPerspective parameter and returns itself.
Definition SwerveRequest.hpp:2043
FieldCentricFacingAngle & WithSteerRequestType(impl::SteerRequestType newSteerRequestType)
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1998
Rotation2d TargetDirection
The desired direction to face.
Definition SwerveRequest.hpp:1725
units::radians_per_second_t MaxAbsRotationalRate
The maximum absolute rotational rate to allow.
Definition SwerveRequest.hpp:1746
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:1712
FieldCentricFacingAngle & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective)
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:2027
FieldCentricFacingAngle & WithTargetDirection(Rotation2d newTargetDirection)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:1895
FieldCentricFacingAngle & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds)
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:2013
PhoenixPIDController HeadingController
The PID controller used to maintain the desired heading.
Definition SwerveRequest.hpp:1787
units::radians_per_second_t TargetRateFeedforward
The rotational rate feedforward to add to the output of the heading controller, in radians per second...
Definition SwerveRequest.hpp:1732
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition SwerveRequest.hpp:1751
FieldCentricFacingAngle()
Definition SwerveRequest.hpp:1789
FieldCentricFacingAngle & WithVelocityY(units::meters_per_second_t newVelocityY)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:1879
FieldCentricFacingAngle & WithVelocityX(units::meters_per_second_t newVelocityX)
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:1863
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:1737
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition SwerveRequest.hpp:1718
FieldCentricFacingAngle & WithDeadband(units::meters_per_second_t newDeadband)
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:1926
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:1741
FieldCentricFacingAngle & WithDriveRequestType(impl::DriveRequestType newDriveRequestType)
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1984
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1794
FieldCentricFacingAngle & WithTargetRateFeedforward(units::radians_per_second_t newTargetRateFeedforward)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:1912
FieldCentricFacingAngle & WithCenterOfRotation(Translation2d newCenterOfRotation)
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1970
FieldCentricFacingAngle & WithHeadingPID(double kP, double kI, double kD)
Modifies the PID gains of the HeadingController parameter and returns itself.
Definition SwerveRequest.hpp:1848
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward.
Definition SwerveRequest.hpp:1770
Drives the swerve drivetrain in a field-centric manner.
Definition SwerveRequest.hpp:189
FieldCentric && WithRotationalRate(units::radians_per_second_t newRotationalRate) &&
Modifies the RotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:369
FieldCentric && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:452
FieldCentric && WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &&
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:423
FieldCentric & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:438
FieldCentric && WithVelocityY(units::meters_per_second_t newVelocityY) &&
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:340
FieldCentric && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:506
FieldCentric & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:410
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:211
FieldCentric & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective) &
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:549
units::radians_per_second_t RotationalRate
The angular rate to rotate at.
Definition SwerveRequest.hpp:207
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition SwerveRequest.hpp:201
FieldCentric & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:493
FieldCentric && WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective) &&
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:562
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:241
FieldCentric && WithDeadband(units::meters_per_second_t newDeadband) &&
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:396
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:195
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition SwerveRequest.hpp:220
FieldCentric && WithVelocityX(units::meters_per_second_t newVelocityX) &&
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:309
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:234
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward.
Definition SwerveRequest.hpp:239
FieldCentric && WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:535
FieldCentric & WithDeadband(units::meters_per_second_t newDeadband) &
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:383
FieldCentric & WithRotationalRate(units::radians_per_second_t newRotationalRate) &
Modifies the RotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:355
FieldCentric & WithVelocityY(units::meters_per_second_t newVelocityY) &
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:325
FieldCentric & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:466
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:215
FieldCentric & WithVelocityX(units::meters_per_second_t newVelocityX) &
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:295
FieldCentric && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:479
FieldCentric & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:521
Does nothing to the swerve module state.
Definition SwerveRequest.hpp:84
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &, std::span< std::unique_ptr< impl::SwerveModuleImpl > const >) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:86
Sets the swerve drive modules to point to a specified direction.
Definition SwerveRequest.hpp:919
PointWheelsAt && WithModuleDirection(Rotation2d newModuleDirection) &&
Modifies the ModuleDirection parameter and returns itself.
Definition SwerveRequest.hpp:971
PointWheelsAt && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:998
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:935
PointWheelsAt && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1025
PointWheelsAt & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:985
PointWheelsAt & WithModuleDirection(Rotation2d newModuleDirection) &
Modifies the ModuleDirection parameter and returns itself.
Definition SwerveRequest.hpp:957
Rotation2d ModuleDirection
The direction to point the modules toward.
Definition SwerveRequest.hpp:925
PointWheelsAt & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1012
Drives the swerve drivetrain in a robot-centric manner, maintaining a specified heading angle to ensu...
Definition SwerveRequest.hpp:2066
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2149
units::radians_per_second_t TargetRateFeedforward
The rotational rate feedforward to add to the output of the heading controller, in radians per second...
Definition SwerveRequest.hpp:2092
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward for the target heading.
Definition SwerveRequest.hpp:2131
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:2097
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition SwerveRequest.hpp:2078
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:2125
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition SwerveRequest.hpp:2111
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:2101
RobotCentricFacingAngle & WithMaxAbsRotationalRate(units::radians_per_second_t newMaxAbsRotationalRate)
Modifies the MaxAbsRotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:2306
RobotCentricFacingAngle & WithTargetRateFeedforward(units::radians_per_second_t newTargetRateFeedforward)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:2263
RobotCentricFacingAngle & WithSteerRequestType(impl::SteerRequestType newSteerRequestType)
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:2349
RobotCentricFacingAngle & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband)
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:2291
RobotCentricFacingAngle & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds)
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:2364
RobotCentricFacingAngle & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective)
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:2379
RobotCentricFacingAngle & WithVelocityY(units::meters_per_second_t newVelocityY)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:2230
RobotCentricFacingAngle()
Definition SwerveRequest.hpp:2144
RobotCentricFacingAngle & WithDeadband(units::meters_per_second_t newDeadband)
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:2277
RobotCentricFacingAngle & WithHeadingPID(double kP, double kI, double kD)
Modifies the PID gains of the HeadingController parameter and returns itself.
Definition SwerveRequest.hpp:2199
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:2072
PhoenixPIDController HeadingController
The PID controller used to maintain the desired heading.
Definition SwerveRequest.hpp:2142
RobotCentricFacingAngle & WithCenterOfRotation(Translation2d newCenterOfRotation)
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:2321
RobotCentricFacingAngle & WithTargetDirection(Rotation2d newTargetDirection)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:2246
Rotation2d TargetDirection
The desired direction to face.
Definition SwerveRequest.hpp:2085
units::radians_per_second_t MaxAbsRotationalRate
The maximum absolute rotational rate to allow.
Definition SwerveRequest.hpp:2106
RobotCentricFacingAngle & WithDriveRequestType(impl::DriveRequestType newDriveRequestType)
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:2335
RobotCentricFacingAngle & WithVelocityX(units::meters_per_second_t newVelocityX)
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:2214
Drives the swerve drivetrain in a robot-centric manner.
Definition SwerveRequest.hpp:582
units::radians_per_second_t RotationalRate
The angular rate to rotate at.
Definition SwerveRequest.hpp:600
RobotCentric & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:784
RobotCentric & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:812
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:628
RobotCentric && WithDeadband(units::meters_per_second_t newDeadband) &&
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:770
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition SwerveRequest.hpp:594
RobotCentric && WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:909
RobotCentric && WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &&
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:797
RobotCentric && WithRotationalRate(units::radians_per_second_t newRotationalRate) &&
Modifies the RotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:743
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:609
RobotCentric && WithVelocityX(units::meters_per_second_t newVelocityX) &&
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:683
RobotCentric & WithDeadband(units::meters_per_second_t newDeadband) &
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:757
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:588
RobotCentric & WithRotationalRate(units::radians_per_second_t newRotationalRate) &
Modifies the RotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:729
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:630
RobotCentric && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:880
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition SwerveRequest.hpp:614
RobotCentric && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:826
RobotCentric && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:853
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:605
RobotCentric & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:840
RobotCentric & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:867
RobotCentric & WithVelocityX(units::meters_per_second_t newVelocityX) &
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:669
RobotCentric & WithVelocityY(units::meters_per_second_t newVelocityY) &
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:699
RobotCentric && WithVelocityY(units::meters_per_second_t newVelocityY) &&
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:714
RobotCentric & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:895
Sets the swerve drive module states to point inward on the robot in an "X" fashion,...
Definition SwerveRequest.hpp:97
SwerveDriveBrake & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:129
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:108
SwerveDriveBrake && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:142
SwerveDriveBrake && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:169
SwerveDriveBrake & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:156
Container for all the Swerve Requests.
Definition SwerveRequest.hpp:63
virtual ctre::phoenix::StatusCode Apply(ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply)=0
Applies this swerve request to the given modules.
SysId-specific SwerveRequest to characterize the rotational characteristics of a swerve drivetrain.
Definition SwerveRequest.hpp:2457
units::radians_per_second_t RotationalRate
The angular rate to rotate at, in radians per second.
Definition SwerveRequest.hpp:2462
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2464
SysIdSwerveRotation && WithRotationalRate(units::radians_per_second_t rotationalRate) &&
Update the angular rate to rotate at, in radians per second.
Definition SwerveRequest.hpp:2507
SysIdSwerveRotation & WithRotationalRate(units::radians_per_second_t rotationalRate) &
Update the angular rate to rotate at, in radians per second.
Definition SwerveRequest.hpp:2496
SysId-specific SwerveRequest to characterize the steer module characteristics of a swerve drivetrain.
Definition SwerveRequest.hpp:2518
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2525
SysIdSwerveSteerGains && WithVolts(units::volt_t volts) &&
Update the voltage to apply to the drive wheels.
Definition SwerveRequest.hpp:2550
units::volt_t VoltsToApply
Voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2523
SysIdSwerveSteerGains & WithVolts(units::volt_t volts) &
Update the voltage to apply to the drive wheels.
Definition SwerveRequest.hpp:2539
SysId-specific SwerveRequest to characterize the translational characteristics of a swerve drivetrain...
Definition SwerveRequest.hpp:2390
SysIdSwerveTranslation & WithVolts(units::volt_t volts) &
Sets the voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2424
SysIdSwerveTranslation && WithVolts(units::volt_t volts) &&
Sets the voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2435
units::volt_t VoltsToApply
Voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2395
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2397
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:28
static constexpr int OK
No Error.
Definition StatusCodes.h:35
SteerRequestType
All possible control requests for the module steer motor.
Definition SwerveModuleImpl.hpp:25
@ Position
Control the drive motor using an unprofiled position request.
DriveRequestType
All possible control requests for the module drive motor.
Definition SwerveModuleImpl.hpp:41
@ OpenLoopVoltage
Control the drive motor using an open-loop voltage request.
ForwardPerspectiveValue
In field-centric control, the direction of "forward" is sometimes different depending on perspective.
Definition SwerveRequest.hpp:21
@ BlueAlliance
"Forward" (positive X) is always from the perspective of the blue alliance (i.e.
@ OperatorPerspective
"Forward" (positive X) is determined from the operator's perspective.
TargetDirectionPerspectiveValue
In field-centric control, the direction of "forward" for the target direction sometimes differs from ...
Definition SwerveRequest.hpp:43
@ UseForwardPerspective
Match the ForwardPerspective parameter for heading control.
Definition motor_constants.h:14
Contains everything the control requests need to calculate the module state.
Definition SwerveDrivetrainImpl.hpp:142
units::second_t timestamp
The timestamp of the current control apply, in the timebase of utils::GetCurrentTime()
Definition SwerveDrivetrainImpl.hpp:157
units::meters_per_second_t kMaxSpeed
The max speed of the robot at 12 V output.
Definition SwerveDrivetrainImpl.hpp:148
units::second_t updatePeriod
The update period of control apply.
Definition SwerveDrivetrainImpl.hpp:159
impl::SwerveDriveKinematics * kinematics
The kinematics object used for control.
Definition SwerveDrivetrainImpl.hpp:144
Pose2d currentPose
The current pose of the robot.
Definition SwerveDrivetrainImpl.hpp:155
Rotation2d operatorForwardDirection
The forward direction from the operator perspective.
Definition SwerveDrivetrainImpl.hpp:151
Translation2d const * moduleLocations
The locations of the swerve modules.
Definition SwerveDrivetrainImpl.hpp:146
Contains everything the swerve module needs to apply a request.
Definition SwerveModuleImpl.hpp:66
ModuleRequest & WithSteerRequest(SteerRequestType newSteerRequest)
Modifies the SteerRequest parameter and returns itself.
Definition SwerveModuleImpl.hpp:190
ModuleRequest & WithDriveRequest(DriveRequestType newDriveRequest)
Modifies the DriveRequest parameter and returns itself.
Definition SwerveModuleImpl.hpp:177
ModuleRequest & WithUpdatePeriod(units::second_t newUpdatePeriod)
Modifies the UpdatePeriod parameter and returns itself.
Definition SwerveModuleImpl.hpp:205