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