WPILibC++ 2023.4.3-108-ge5452e3
|
A command that uses two PID controllers (PIDController) and a profiled PID controller (ProfiledPIDController) to follow a trajectory (Trajectory) with a mecanum drive. More...
#include <frc2/command/MecanumControllerCommand.h>
Public Member Functions | |
MecanumControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, units::meters_per_second_t maxWheelVelocity, std::function< frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds, frc2::PIDController frontLeftController, frc2::PIDController rearLeftController, frc2::PIDController frontRightController, frc2::PIDController rearRightController, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, std::initializer_list< Subsystem * > requirements) | |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory. More... | |
MecanumControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, units::meters_per_second_t maxWheelVelocity, std::function< frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds, frc2::PIDController frontLeftController, frc2::PIDController rearLeftController, frc2::PIDController frontRightController, frc2::PIDController rearRightController, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, std::initializer_list< Subsystem * > requirements) | |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory. More... | |
MecanumControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, units::meters_per_second_t maxWheelVelocity, std::function< frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds, frc2::PIDController frontLeftController, frc2::PIDController rearLeftController, frc2::PIDController frontRightController, frc2::PIDController rearRightController, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, std::span< Subsystem *const > requirements={}) | |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory. More... | |
MecanumControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, units::meters_per_second_t maxWheelVelocity, std::function< frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds, frc2::PIDController frontLeftController, frc2::PIDController rearLeftController, frc2::PIDController frontRightController, frc2::PIDController rearRightController, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, std::span< Subsystem *const > requirements={}) | |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory. More... | |
MecanumControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, units::meters_per_second_t maxWheelVelocity, std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> output, std::initializer_list< Subsystem * > requirements) | |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory. More... | |
MecanumControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, units::meters_per_second_t maxWheelVelocity, std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> output, std::initializer_list< Subsystem * > requirements) | |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory. More... | |
MecanumControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, units::meters_per_second_t maxWheelVelocity, std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> output, std::span< Subsystem *const > requirements={}) | |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory. More... | |
MecanumControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, units::meters_per_second_t maxWheelVelocity, std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> output, std::span< Subsystem *const > requirements={}) | |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory. More... | |
void | Initialize () override |
void | Execute () override |
void | End (bool interrupted) override |
bool | IsFinished () override |
Public Member Functions inherited from frc2::CommandHelper< CommandBase, MecanumControllerCommand > | |
CommandHelper ()=default | |
CommandPtr | ToPtr () &&override |
Additional Inherited Members | |
Protected Member Functions inherited from frc2::CommandHelper< CommandBase, MecanumControllerCommand > | |
std::unique_ptr< Command > | TransferOwnership () &&override |
A command that uses two PID controllers (PIDController) and a profiled PID controller (ProfiledPIDController) to follow a trajectory (Trajectory) with a mecanum drive.
The command handles trajectory-following, Velocity PID calculations, and feedforwards internally. This is intended to be a more-or-less "complete solution" that can be used by teams without a great deal of controls expertise.
Advanced teams seeking more flexibility (for example, those who wish to use the onboard PID functionality of a "smart" motor controller) may use the secondary constructor that omits the PID and feedforward functionality, returning only the raw wheel speeds from the PID controllers.
The robot angle controller does not follow the angle given by the trajectory but rather goes to the angle given in the final state of the trajectory.
This class is provided by the NewCommands VendorDep
frc2::MecanumControllerCommand::MecanumControllerCommand | ( | frc::Trajectory | trajectory, |
std::function< frc::Pose2d()> | pose, | ||
frc::SimpleMotorFeedforward< units::meters > | feedforward, | ||
frc::MecanumDriveKinematics | kinematics, | ||
frc2::PIDController | xController, | ||
frc2::PIDController | yController, | ||
frc::ProfiledPIDController< units::radians > | thetaController, | ||
std::function< frc::Rotation2d()> | desiredRotation, | ||
units::meters_per_second_t | maxWheelVelocity, | ||
std::function< frc::MecanumDriveWheelSpeeds()> | currentWheelSpeeds, | ||
frc2::PIDController | frontLeftController, | ||
frc2::PIDController | rearLeftController, | ||
frc2::PIDController | frontRightController, | ||
frc2::PIDController | rearRightController, | ||
std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> | output, | ||
std::initializer_list< Subsystem * > | requirements | ||
) |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
PID control and feedforward are handled internally. Outputs are scaled from -12 to 12 as a voltage output to the motor.
Note: The controllers will not set the outputVolts to zero upon completion of the path this is left to the user, since it is not appropriate for paths with nonstationary endstates.
trajectory | The trajectory to follow. |
pose | A function that supplies the robot pose, provided by the odometry class. |
feedforward | The feedforward to use for the drivetrain. |
kinematics | The kinematics for the robot drivetrain. |
xController | The Trajectory Tracker PID controller for the robot's x position. |
yController | The Trajectory Tracker PID controller for the robot's y position. |
thetaController | The Trajectory Tracker PID controller for angle for the robot. |
desiredRotation | The angle that the robot should be facing. This is sampled at each time step. |
maxWheelVelocity | The maximum velocity of a drivetrain wheel. |
frontLeftController | The front left wheel velocity PID. |
rearLeftController | The rear left wheel velocity PID. |
frontRightController | The front right wheel velocity PID. |
rearRightController | The rear right wheel velocity PID. |
currentWheelSpeeds | A MecanumDriveWheelSpeeds object containing the current wheel speeds. |
output | The output of the velocity PIDs. |
requirements | The subsystems to require. |
frc2::MecanumControllerCommand::MecanumControllerCommand | ( | frc::Trajectory | trajectory, |
std::function< frc::Pose2d()> | pose, | ||
frc::SimpleMotorFeedforward< units::meters > | feedforward, | ||
frc::MecanumDriveKinematics | kinematics, | ||
frc2::PIDController | xController, | ||
frc2::PIDController | yController, | ||
frc::ProfiledPIDController< units::radians > | thetaController, | ||
units::meters_per_second_t | maxWheelVelocity, | ||
std::function< frc::MecanumDriveWheelSpeeds()> | currentWheelSpeeds, | ||
frc2::PIDController | frontLeftController, | ||
frc2::PIDController | rearLeftController, | ||
frc2::PIDController | frontRightController, | ||
frc2::PIDController | rearRightController, | ||
std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> | output, | ||
std::initializer_list< Subsystem * > | requirements | ||
) |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
PID control and feedforward are handled internally. Outputs are scaled from -12 to 12 as a voltage output to the motor.
Note: The controllers will not set the outputVolts to zero upon completion of the path this is left to the user, since it is not appropriate for paths with nonstationary endstates.
Note 2: The final rotation of the robot will be set to the rotation of the final pose in the trajectory. The robot will not follow the rotations from the poses at each timestep. If alternate rotation behavior is desired, the other constructor with a supplier for rotation should be used.
trajectory | The trajectory to follow. |
pose | A function that supplies the robot pose, provided by the odometry class. |
feedforward | The feedforward to use for the drivetrain. |
kinematics | The kinematics for the robot drivetrain. |
xController | The Trajectory Tracker PID controller for the robot's x position. |
yController | The Trajectory Tracker PID controller for the robot's y position. |
thetaController | The Trajectory Tracker PID controller for angle for the robot. |
maxWheelVelocity | The maximum velocity of a drivetrain wheel. |
frontLeftController | The front left wheel velocity PID. |
rearLeftController | The rear left wheel velocity PID. |
frontRightController | The front right wheel velocity PID. |
rearRightController | The rear right wheel velocity PID. |
currentWheelSpeeds | A MecanumDriveWheelSpeeds object containing the current wheel speeds. |
output | The output of the velocity PIDs. |
requirements | The subsystems to require. |
frc2::MecanumControllerCommand::MecanumControllerCommand | ( | frc::Trajectory | trajectory, |
std::function< frc::Pose2d()> | pose, | ||
frc::SimpleMotorFeedforward< units::meters > | feedforward, | ||
frc::MecanumDriveKinematics | kinematics, | ||
frc2::PIDController | xController, | ||
frc2::PIDController | yController, | ||
frc::ProfiledPIDController< units::radians > | thetaController, | ||
std::function< frc::Rotation2d()> | desiredRotation, | ||
units::meters_per_second_t | maxWheelVelocity, | ||
std::function< frc::MecanumDriveWheelSpeeds()> | currentWheelSpeeds, | ||
frc2::PIDController | frontLeftController, | ||
frc2::PIDController | rearLeftController, | ||
frc2::PIDController | frontRightController, | ||
frc2::PIDController | rearRightController, | ||
std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> | output, | ||
std::span< Subsystem *const > | requirements = {} |
||
) |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
PID control and feedforward are handled internally. Outputs are scaled from -12 to 12 as a voltage output to the motor.
Note: The controllers will not set the outputVolts to zero upon completion of the path this is left to the user, since it is not appropriate for paths with nonstationary endstates.
trajectory | The trajectory to follow. |
pose | A function that supplies the robot pose, provided by the odometry class. |
feedforward | The feedforward to use for the drivetrain. |
kinematics | The kinematics for the robot drivetrain. |
xController | The Trajectory Tracker PID controller for the robot's x position. |
yController | The Trajectory Tracker PID controller for the robot's y position. |
thetaController | The Trajectory Tracker PID controller for angle for the robot. |
desiredRotation | The angle that the robot should be facing. This is sampled at each time step. |
maxWheelVelocity | The maximum velocity of a drivetrain wheel. |
frontLeftController | The front left wheel velocity PID. |
rearLeftController | The rear left wheel velocity PID. |
frontRightController | The front right wheel velocity PID. |
rearRightController | The rear right wheel velocity PID. |
currentWheelSpeeds | A MecanumDriveWheelSpeeds object containing the current wheel speeds. |
output | The output of the velocity PIDs. |
requirements | The subsystems to require. |
frc2::MecanumControllerCommand::MecanumControllerCommand | ( | frc::Trajectory | trajectory, |
std::function< frc::Pose2d()> | pose, | ||
frc::SimpleMotorFeedforward< units::meters > | feedforward, | ||
frc::MecanumDriveKinematics | kinematics, | ||
frc2::PIDController | xController, | ||
frc2::PIDController | yController, | ||
frc::ProfiledPIDController< units::radians > | thetaController, | ||
units::meters_per_second_t | maxWheelVelocity, | ||
std::function< frc::MecanumDriveWheelSpeeds()> | currentWheelSpeeds, | ||
frc2::PIDController | frontLeftController, | ||
frc2::PIDController | rearLeftController, | ||
frc2::PIDController | frontRightController, | ||
frc2::PIDController | rearRightController, | ||
std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> | output, | ||
std::span< Subsystem *const > | requirements = {} |
||
) |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
PID control and feedforward are handled internally. Outputs are scaled from -12 to 12 as a voltage output to the motor.
Note: The controllers will not set the outputVolts to zero upon completion of the path this is left to the user, since it is not appropriate for paths with nonstationary endstates.
Note 2: The final rotation of the robot will be set to the rotation of the final pose in the trajectory. The robot will not follow the rotations from the poses at each timestep. If alternate rotation behavior is desired, the other constructor with a supplier for rotation should be used.
trajectory | The trajectory to follow. |
pose | A function that supplies the robot pose, provided by the odometry class. |
feedforward | The feedforward to use for the drivetrain. |
kinematics | The kinematics for the robot drivetrain. |
xController | The Trajectory Tracker PID controller for the robot's x position. |
yController | The Trajectory Tracker PID controller for the robot's y position. |
thetaController | The Trajectory Tracker PID controller for angle for the robot. |
maxWheelVelocity | The maximum velocity of a drivetrain wheel. |
frontLeftController | The front left wheel velocity PID. |
rearLeftController | The rear left wheel velocity PID. |
frontRightController | The front right wheel velocity PID. |
rearRightController | The rear right wheel velocity PID. |
currentWheelSpeeds | A MecanumDriveWheelSpeeds object containing the current wheel speeds. |
output | The output of the velocity PIDs. |
requirements | The subsystems to require. |
frc2::MecanumControllerCommand::MecanumControllerCommand | ( | frc::Trajectory | trajectory, |
std::function< frc::Pose2d()> | pose, | ||
frc::MecanumDriveKinematics | kinematics, | ||
frc2::PIDController | xController, | ||
frc2::PIDController | yController, | ||
frc::ProfiledPIDController< units::radians > | thetaController, | ||
std::function< frc::Rotation2d()> | desiredRotation, | ||
units::meters_per_second_t | maxWheelVelocity, | ||
std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> | output, | ||
std::initializer_list< Subsystem * > | requirements | ||
) |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
The user should implement a velocity PID on the desired output wheel velocities.
Note: The controllers will not set the outputVolts to zero upon completion of the path - this is left to the user, since it is not appropriate for paths with nonstationary end-states.
trajectory | The trajectory to follow. |
pose | A function that supplies the robot pose - use one of the odometry classes to provide this. |
kinematics | The kinematics for the robot drivetrain. |
xController | The Trajectory Tracker PID controller for the robot's x position. |
yController | The Trajectory Tracker PID controller for the robot's y position. |
thetaController | The Trajectory Tracker PID controller for angle for the robot. |
desiredRotation | The angle that the robot should be facing. This is sampled at each time step. |
maxWheelVelocity | The maximum velocity of a drivetrain wheel. |
output | The output of the position PIDs. |
requirements | The subsystems to require. |
frc2::MecanumControllerCommand::MecanumControllerCommand | ( | frc::Trajectory | trajectory, |
std::function< frc::Pose2d()> | pose, | ||
frc::MecanumDriveKinematics | kinematics, | ||
frc2::PIDController | xController, | ||
frc2::PIDController | yController, | ||
frc::ProfiledPIDController< units::radians > | thetaController, | ||
units::meters_per_second_t | maxWheelVelocity, | ||
std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> | output, | ||
std::initializer_list< Subsystem * > | requirements | ||
) |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
The user should implement a velocity PID on the desired output wheel velocities.
Note: The controllers will not set the outputVolts to zero upon completion of the path - this is left to the user, since it is not appropriate for paths with nonstationary end-states.
Note 2: The final rotation of the robot will be set to the rotation of the final pose in the trajectory. The robot will not follow the rotations from the poses at each timestep. If alternate rotation behavior is desired, the other constructor with a supplier for rotation should be used.
trajectory | The trajectory to follow. |
pose | A function that supplies the robot pose - use one of the odometry classes to provide this. |
kinematics | The kinematics for the robot drivetrain. |
xController | The Trajectory Tracker PID controller for the robot's x position. |
yController | The Trajectory Tracker PID controller for the robot's y position. |
thetaController | The Trajectory Tracker PID controller for angle for the robot. |
maxWheelVelocity | The maximum velocity of a drivetrain wheel. |
output | The output of the position PIDs. |
requirements | The subsystems to require. |
frc2::MecanumControllerCommand::MecanumControllerCommand | ( | frc::Trajectory | trajectory, |
std::function< frc::Pose2d()> | pose, | ||
frc::MecanumDriveKinematics | kinematics, | ||
frc2::PIDController | xController, | ||
frc2::PIDController | yController, | ||
frc::ProfiledPIDController< units::radians > | thetaController, | ||
std::function< frc::Rotation2d()> | desiredRotation, | ||
units::meters_per_second_t | maxWheelVelocity, | ||
std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> | output, | ||
std::span< Subsystem *const > | requirements = {} |
||
) |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
The user should implement a velocity PID on the desired output wheel velocities.
Note: The controllers will not set the outputVolts to zero upon completion of the path - this is left to the user, since it is not appropriate for paths with nonstationary end-states.
trajectory | The trajectory to follow. |
pose | A function that supplies the robot pose - use one of the odometry classes to provide this. |
kinematics | The kinematics for the robot drivetrain. |
xController | The Trajectory Tracker PID controller for the robot's x position. |
yController | The Trajectory Tracker PID controller for the robot's y position. |
thetaController | The Trajectory Tracker PID controller for angle for the robot. |
desiredRotation | The angle that the robot should be facing. This is sampled at every time step. |
maxWheelVelocity | The maximum velocity of a drivetrain wheel. |
output | The output of the position PIDs. |
requirements | The subsystems to require. |
frc2::MecanumControllerCommand::MecanumControllerCommand | ( | frc::Trajectory | trajectory, |
std::function< frc::Pose2d()> | pose, | ||
frc::MecanumDriveKinematics | kinematics, | ||
frc2::PIDController | xController, | ||
frc2::PIDController | yController, | ||
frc::ProfiledPIDController< units::radians > | thetaController, | ||
units::meters_per_second_t | maxWheelVelocity, | ||
std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> | output, | ||
std::span< Subsystem *const > | requirements = {} |
||
) |
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
The user should implement a velocity PID on the desired output wheel velocities.
Note: The controllers will not set the outputVolts to zero upon completion of the path - this is left to the user, since it is not appropriate for paths with nonstationary end-states.
Note2: The final rotation of the robot will be set to the rotation of the final pose in the trajectory. The robot will not follow the rotations from the poses at each timestep. If alternate rotation behavior is desired, the other constructor with a supplier for rotation should be used.
trajectory | The trajectory to follow. |
pose | A function that supplies the robot pose - use one of the odometry classes to provide this. |
kinematics | The kinematics for the robot drivetrain. |
xController | The Trajectory Tracker PID controller for the robot's x position. |
yController | The Trajectory Tracker PID controller for the robot's y position. |
thetaController | The Trajectory Tracker PID controller for angle for the robot. |
maxWheelVelocity | The maximum velocity of a drivetrain wheel. |
output | The output of the position PIDs. |
requirements | The subsystems to require. |
|
override |
|
override |
|
override |
|
override |