97 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
98 modulesToApply[i]->Apply(moduleRequest.WithState({0_mps, parameters.moduleLocations[i].Angle()}));
114 this->DriveRequestType = std::move(newDriveRequestType);
127 this->DriveRequestType = std::move(newDriveRequestType);
128 return std::move(*
this);
141 this->SteerRequestType = std::move(newSteerRequestType);
154 this->SteerRequestType = std::move(newSteerRequestType);
155 return std::move(*
this);
231 Translation2d tmp{toApplyX * 1_s, toApplyY * 1_s};
233 toApplyX = tmp.X() / 1_s;
234 toApplyY = tmp.Y() / 1_s;
237 if (units::math::hypot(toApplyX, toApplyY) <
Deadband) {
242 toApplyOmega = 0_rad_per_s;
245 auto const speeds = ChassisSpeeds::Discretize(
246 ChassisSpeeds::FromFieldRelativeSpeeds(
247 {toApplyX, toApplyY, toApplyOmega}, parameters.
currentPose.Rotation()
261 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
262 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
279 this->VelocityX = std::move(newVelocityX);
293 this->VelocityX = std::move(newVelocityX);
294 return std::move(*
this);
309 this->VelocityY = std::move(newVelocityY);
324 this->VelocityY = std::move(newVelocityY);
325 return std::move(*
this);
339 this->RotationalRate = std::move(newRotationalRate);
353 this->RotationalRate = std::move(newRotationalRate);
354 return std::move(*
this);
367 this->Deadband = std::move(newDeadband);
380 this->Deadband = std::move(newDeadband);
381 return std::move(*
this);
394 this->RotationalDeadband = std::move(newRotationalDeadband);
407 this->RotationalDeadband = std::move(newRotationalDeadband);
408 return std::move(*
this);
437 return std::move(*
this);
450 this->DriveRequestType = std::move(newDriveRequestType);
463 this->DriveRequestType = std::move(newDriveRequestType);
464 return std::move(*
this);
477 this->SteerRequestType = std::move(newSteerRequestType);
490 this->SteerRequestType = std::move(newSteerRequestType);
491 return std::move(*
this);
505 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
519 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
520 return std::move(*
this);
533 this->ForwardPerspective = std::move(newForwardPerspective);
546 this->ForwardPerspective = std::move(newForwardPerspective);
547 return std::move(*
this);
616 if (units::math::hypot(toApplyX, toApplyY) <
Deadband) {
621 toApplyOmega = 0_rad_per_s;
623 ChassisSpeeds
const speeds{toApplyX, toApplyY, toApplyOmega};
634 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
635 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
652 this->VelocityX = std::move(newVelocityX);
666 this->VelocityX = std::move(newVelocityX);
667 return std::move(*
this);
682 this->VelocityY = std::move(newVelocityY);
697 this->VelocityY = std::move(newVelocityY);
698 return std::move(*
this);
712 this->RotationalRate = std::move(newRotationalRate);
726 this->RotationalRate = std::move(newRotationalRate);
727 return std::move(*
this);
740 this->Deadband = std::move(newDeadband);
753 this->Deadband = std::move(newDeadband);
754 return std::move(*
this);
767 this->RotationalDeadband = std::move(newRotationalDeadband);
780 this->RotationalDeadband = std::move(newRotationalDeadband);
781 return std::move(*
this);
810 return std::move(*
this);
823 this->DriveRequestType = std::move(newDriveRequestType);
836 this->DriveRequestType = std::move(newDriveRequestType);
837 return std::move(*
this);
850 this->SteerRequestType = std::move(newSteerRequestType);
863 this->SteerRequestType = std::move(newSteerRequestType);
864 return std::move(*
this);
878 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
892 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
893 return std::move(*
this);
922 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
923 modulesToApply[i]->Apply(moduleRequest.WithState({0_mps, ModuleDirection}));
955 return std::move(*
this);
968 this->DriveRequestType = std::move(newDriveRequestType);
981 this->DriveRequestType = std::move(newDriveRequestType);
982 return std::move(*
this);
995 this->SteerRequestType = std::move(newSteerRequestType);
1008 this->SteerRequestType = std::move(newSteerRequestType);
1009 return std::move(*
this);
1073 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
1078 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
1094 this->
Speeds = std::move(newSpeeds);
1107 this->
Speeds = std::move(newSpeeds);
1108 return std::move(*
this);
1128 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1148 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1149 return std::move(*
this);
1169 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1189 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1190 return std::move(*
this);
1219 return std::move(*
this);
1232 this->DriveRequestType = std::move(newDriveRequestType);
1245 this->DriveRequestType = std::move(newDriveRequestType);
1246 return std::move(*
this);
1259 this->SteerRequestType = std::move(newSteerRequestType);
1272 this->SteerRequestType = std::move(newSteerRequestType);
1273 return std::move(*
this);
1287 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1301 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1302 return std::move(*
this);
1362 auto fieldSpeeds =
Speeds;
1367 fieldSpeeds.vx = tmp.X() / 1_s;
1368 fieldSpeeds.vy = tmp.Y() / 1_s;
1371 auto const robotSpeeds = ChassisSpeeds::Discretize(
1372 ChassisSpeeds::FromFieldRelativeSpeeds(
1388 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
1393 Translation2d tmp{wheelForceFeedforwardX * 1_m/1_N, wheelForceFeedforwardY * 1_m/1_N};
1399 tmp = tmp.RotateBy(-parameters.
currentPose.Rotation());
1401 wheelForceFeedforwardX = tmp.X() * 1_N/1_m;
1402 wheelForceFeedforwardY = tmp.Y() * 1_N/1_m;
1408 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
1424 this->
Speeds = std::move(newSpeeds);
1437 this->
Speeds = std::move(newSpeeds);
1438 return std::move(*
this);
1458 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1478 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1479 return std::move(*
this);
1499 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1519 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1520 return std::move(*
this);
1549 return std::move(*
this);
1562 this->DriveRequestType = std::move(newDriveRequestType);
1575 this->DriveRequestType = std::move(newDriveRequestType);
1576 return std::move(*
this);
1589 this->SteerRequestType = std::move(newSteerRequestType);
1602 this->SteerRequestType = std::move(newSteerRequestType);
1603 return std::move(*
this);
1617 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1631 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1632 return std::move(*
this);
1645 this->ForwardPerspective = std::move(newForwardPerspective);
1658 this->ForwardPerspective = std::move(newForwardPerspective);
1659 return std::move(*
this);
1765 parameters.
currentPose.Rotation().Radians().value(),
1766 angleToFace.Radians().value(),
1781 .
Apply(parameters, modulesToApply);
1795 this->VelocityX = std::move(newVelocityX);
1811 this->VelocityY = std::move(newVelocityY);
1844 this->TargetRateFeedforward = std::move(newTargetRateFeedforward);
1858 this->Deadband = std::move(newDeadband);
1872 this->RotationalDeadband = std::move(newRotationalDeadband);
1901 this->DriveRequestType = std::move(newDriveRequestType);
1915 this->SteerRequestType = std::move(newSteerRequestType);
1930 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1944 this->ForwardPerspective = std::move(newForwardPerspective);
1962 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
1976 this->VoltsToApply = volts;
1987 this->VoltsToApply = volts;
1988 return std::move(*
this);
2016 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
2018 auto const angle = parameters.
moduleLocations[i].Angle() + Rotation2d{90_deg};
2019 modulesToApply[i]->Apply(
2035 this->RotationalRate = rotationalRate;
2046 this->RotationalRate = rotationalRate;
2047 return std::move(*
this);
2064 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
2078 this->VoltsToApply = volts;
2089 this->VoltsToApply = volts;
2090 return std::move(*
this);
Request coast neutral output of actuator.
Definition CoastOut.hpp:27
Request PID to target position with voltage feedforward.
Definition PositionVoltage.hpp:31
Request a specified voltage.
Definition VoltageOut.hpp:29
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.
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 ¢erOfRotation=Translation2d{})
Performs inverse kinematics to return the module states from a desired chassis velocity.
DriveRequestType
All possible control requests for the module drive motor.
Definition SwerveModuleImpl.hpp:50
@ OpenLoopVoltage
Control the drive motor using an open-loop voltage request.
SteerRequestType
All possible control requests for the module steer motor.
Definition SwerveModuleImpl.hpp:34
@ Position
Control the drive motor using an unprofiled position request.
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 & WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1560
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 && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1546
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1360
ApplyFieldSpeeds && WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1573
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition SwerveRequest.hpp:1344
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
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition SwerveRequest.hpp:1348
ApplyFieldSpeeds & WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1456
std::vector< units::newton_t > WheelForceFeedforwardsX
Field-centric wheel force feedforwards to apply in the X direction.
Definition SwerveRequest.hpp:1325
ApplyFieldSpeeds & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1587
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 && WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1600
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
ChassisSpeeds Speeds
The robot-centric chassis speeds to apply to the drivetrain.
Definition SwerveRequest.hpp:1021
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1062
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition SwerveRequest.hpp:1055
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition SwerveRequest.hpp:1051
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::SwerveModuleImpl::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::SwerveModuleImpl::SteerRequestType newSteerRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1270
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 & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &
Modifies the DriveRequestType 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:1187
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 && WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1243
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:1732
FieldCentricFacingAngle & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband)
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:1870
FieldCentricFacingAngle & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType newSteerRequestType)
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1913
Rotation2d TargetDirection
The desired direction to face.
Definition SwerveRequest.hpp:1697
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:1684
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition SwerveRequest.hpp:1723
FieldCentricFacingAngle & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective)
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:1942
FieldCentricFacingAngle & WithTargetDirection(Rotation2d newTargetDirection)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:1825
FieldCentricFacingAngle & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds)
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1928
FieldCentricFacingAngle & WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType newDriveRequestType)
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1899
PhoenixPIDController HeadingController
The PID controller used to maintain the desired heading.
Definition SwerveRequest.hpp:1748
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition SwerveRequest.hpp:1727
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:1718
FieldCentricFacingAngle()
Definition SwerveRequest.hpp:1750
FieldCentricFacingAngle & WithVelocityY(units::meters_per_second_t newVelocityY)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:1809
FieldCentricFacingAngle & WithVelocityX(units::meters_per_second_t newVelocityX)
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:1793
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:1709
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1755
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:1856
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:1713
FieldCentricFacingAngle & WithTargetRateFeedforward(units::radians_per_second_t newTargetRateFeedforward)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:1842
FieldCentricFacingAngle & WithCenterOfRotation(Translation2d newCenterOfRotation)
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1885
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward.
Definition SwerveRequest.hpp:1737
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
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition SwerveRequest.hpp:207
FieldCentric & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:420
FieldCentric && WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:488
FieldCentric && WithVelocityY(units::meters_per_second_t newVelocityY) &&
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:322
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 && 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
FieldCentric && WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:461
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:223
FieldCentric & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:475
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
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition SwerveRequest.hpp:211
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
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::SwerveModuleImpl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:448
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::SwerveModuleImpl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:966
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition SwerveRequest.hpp:914
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, 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::SwerveModuleImpl::SteerRequestType newSteerRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1006
PointWheelsAt & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:993
PointWheelsAt && WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:979
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
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition SwerveRequest.hpp:910
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 && WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:861
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 & WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:821
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 & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:848
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:586
RobotCentric && WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:834
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition SwerveRequest.hpp:604
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 ¶meters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:611
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition SwerveRequest.hpp:600
Sets the swerve drive module states to point inward on the robot in an "X" fashion,...
Definition SwerveRequest.hpp:80
SwerveDriveBrake && WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:152
SwerveDriveBrake & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:139
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition SwerveRequest.hpp:89
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition SwerveRequest.hpp:85
SwerveDriveBrake && WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:125
SwerveDriveBrake & WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:112
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:91
Container for all the Swerve Requests.
Definition SwerveRequest.hpp:46
virtual ~SwerveRequest()=default
virtual ctre::phoenix::StatusCode Apply(ControlParameters const ¶meters, 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:2007
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2014
units::radians_per_second_t RotationalRate
The angular rate to rotate at, in radians per second.
Definition SwerveRequest.hpp:2012
SysIdSwerveRotation && WithRotationalRate(units::radians_per_second_t rotationalRate) &&
Update the angular rate to rotate at, in radians per second.
Definition SwerveRequest.hpp:2044
SysIdSwerveRotation & WithRotationalRate(units::radians_per_second_t rotationalRate) &
Update the angular rate to rotate at, in radians per second.
Definition SwerveRequest.hpp:2033
SysId-specific SwerveRequest to characterize the steer module characteristics of a swerve drivetrain.
Definition SwerveRequest.hpp:2055
SysIdSwerveSteerGains && WithVolts(units::volt_t volts) &&
Update the voltage to apply to the drive wheels.
Definition SwerveRequest.hpp:2087
units::volt_t VoltsToApply
Voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2060
SysIdSwerveSteerGains & WithVolts(units::volt_t volts) &
Update the voltage to apply to the drive wheels.
Definition SwerveRequest.hpp:2076
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2062
SysId-specific SwerveRequest to characterize the translational characteristics of a swerve drivetrain...
Definition SwerveRequest.hpp:1953
SysIdSwerveTranslation & WithVolts(units::volt_t volts) &
Sets the voltage to apply to drive wheels.
Definition SwerveRequest.hpp:1974
SysIdSwerveTranslation && WithVolts(units::volt_t volts) &&
Sets the voltage to apply to drive wheels.
Definition SwerveRequest.hpp:1985
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1960
units::volt_t VoltsToApply
Voltage to apply to drive wheels.
Definition SwerveRequest.hpp:1958
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:27
static constexpr int OK
No Error.
Definition StatusCodes.h:34
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 StatusCodes.h: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 & WithWheelForceFeedforwardY(units::newton_t newWheelForceFeedforwardY)
Modifies the WheelForceFeedforwardY parameter and returns itself.
Definition SwerveModuleImpl.hpp:162
ModuleRequest & WithDriveRequest(DriveRequestType newDriveRequest)
Modifies the DriveRequest parameter and returns itself.
Definition SwerveModuleImpl.hpp:176
ModuleRequest & WithWheelForceFeedforwardX(units::newton_t newWheelForceFeedforwardX)
Modifies the WheelForceFeedforwardX parameter and returns itself.
Definition SwerveModuleImpl.hpp:145
ModuleRequest & WithUpdatePeriod(units::second_t newUpdatePeriod)
Modifies the UpdatePeriod parameter and returns itself.
Definition SwerveModuleImpl.hpp:204