WPILibC++ 2023.4.3-108-ge5452e3
frc2::MecanumControllerCommand Class Reference

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>

Inheritance diagram for frc2::MecanumControllerCommand:
frc2::CommandHelper< CommandBase, MecanumControllerCommand >

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< CommandTransferOwnership () &&override
 

Detailed Description

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

Constructor & Destructor Documentation

◆ MecanumControllerCommand() [1/8]

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.

Parameters
trajectoryThe trajectory to follow.
poseA function that supplies the robot pose, provided by the odometry class.
feedforwardThe feedforward to use for the drivetrain.
kinematicsThe kinematics for the robot drivetrain.
xControllerThe Trajectory Tracker PID controller for the robot's x position.
yControllerThe Trajectory Tracker PID controller for the robot's y position.
thetaControllerThe Trajectory Tracker PID controller for angle for the robot.
desiredRotationThe angle that the robot should be facing. This is sampled at each time step.
maxWheelVelocityThe maximum velocity of a drivetrain wheel.
frontLeftControllerThe front left wheel velocity PID.
rearLeftControllerThe rear left wheel velocity PID.
frontRightControllerThe front right wheel velocity PID.
rearRightControllerThe rear right wheel velocity PID.
currentWheelSpeedsA MecanumDriveWheelSpeeds object containing the current wheel speeds.
outputThe output of the velocity PIDs.
requirementsThe subsystems to require.

◆ MecanumControllerCommand() [2/8]

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.

Parameters
trajectoryThe trajectory to follow.
poseA function that supplies the robot pose, provided by the odometry class.
feedforwardThe feedforward to use for the drivetrain.
kinematicsThe kinematics for the robot drivetrain.
xControllerThe Trajectory Tracker PID controller for the robot's x position.
yControllerThe Trajectory Tracker PID controller for the robot's y position.
thetaControllerThe Trajectory Tracker PID controller for angle for the robot.
maxWheelVelocityThe maximum velocity of a drivetrain wheel.
frontLeftControllerThe front left wheel velocity PID.
rearLeftControllerThe rear left wheel velocity PID.
frontRightControllerThe front right wheel velocity PID.
rearRightControllerThe rear right wheel velocity PID.
currentWheelSpeedsA MecanumDriveWheelSpeeds object containing the current wheel speeds.
outputThe output of the velocity PIDs.
requirementsThe subsystems to require.

◆ MecanumControllerCommand() [3/8]

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.

Parameters
trajectoryThe trajectory to follow.
poseA function that supplies the robot pose, provided by the odometry class.
feedforwardThe feedforward to use for the drivetrain.
kinematicsThe kinematics for the robot drivetrain.
xControllerThe Trajectory Tracker PID controller for the robot's x position.
yControllerThe Trajectory Tracker PID controller for the robot's y position.
thetaControllerThe Trajectory Tracker PID controller for angle for the robot.
desiredRotationThe angle that the robot should be facing. This is sampled at each time step.
maxWheelVelocityThe maximum velocity of a drivetrain wheel.
frontLeftControllerThe front left wheel velocity PID.
rearLeftControllerThe rear left wheel velocity PID.
frontRightControllerThe front right wheel velocity PID.
rearRightControllerThe rear right wheel velocity PID.
currentWheelSpeedsA MecanumDriveWheelSpeeds object containing the current wheel speeds.
outputThe output of the velocity PIDs.
requirementsThe subsystems to require.

◆ MecanumControllerCommand() [4/8]

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.

Parameters
trajectoryThe trajectory to follow.
poseA function that supplies the robot pose, provided by the odometry class.
feedforwardThe feedforward to use for the drivetrain.
kinematicsThe kinematics for the robot drivetrain.
xControllerThe Trajectory Tracker PID controller for the robot's x position.
yControllerThe Trajectory Tracker PID controller for the robot's y position.
thetaControllerThe Trajectory Tracker PID controller for angle for the robot.
maxWheelVelocityThe maximum velocity of a drivetrain wheel.
frontLeftControllerThe front left wheel velocity PID.
rearLeftControllerThe rear left wheel velocity PID.
frontRightControllerThe front right wheel velocity PID.
rearRightControllerThe rear right wheel velocity PID.
currentWheelSpeedsA MecanumDriveWheelSpeeds object containing the current wheel speeds.
outputThe output of the velocity PIDs.
requirementsThe subsystems to require.

◆ MecanumControllerCommand() [5/8]

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.

Parameters
trajectoryThe trajectory to follow.
poseA function that supplies the robot pose - use one of the odometry classes to provide this.
kinematicsThe kinematics for the robot drivetrain.
xControllerThe Trajectory Tracker PID controller for the robot's x position.
yControllerThe Trajectory Tracker PID controller for the robot's y position.
thetaControllerThe Trajectory Tracker PID controller for angle for the robot.
desiredRotationThe angle that the robot should be facing. This is sampled at each time step.
maxWheelVelocityThe maximum velocity of a drivetrain wheel.
outputThe output of the position PIDs.
requirementsThe subsystems to require.

◆ MecanumControllerCommand() [6/8]

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.

Parameters
trajectoryThe trajectory to follow.
poseA function that supplies the robot pose - use one of the odometry classes to provide this.
kinematicsThe kinematics for the robot drivetrain.
xControllerThe Trajectory Tracker PID controller for the robot's x position.
yControllerThe Trajectory Tracker PID controller for the robot's y position.
thetaControllerThe Trajectory Tracker PID controller for angle for the robot.
maxWheelVelocityThe maximum velocity of a drivetrain wheel.
outputThe output of the position PIDs.
requirementsThe subsystems to require.

◆ MecanumControllerCommand() [7/8]

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.

Parameters
trajectoryThe trajectory to follow.
poseA function that supplies the robot pose - use one of the odometry classes to provide this.
kinematicsThe kinematics for the robot drivetrain.
xControllerThe Trajectory Tracker PID controller for the robot's x position.
yControllerThe Trajectory Tracker PID controller for the robot's y position.
thetaControllerThe Trajectory Tracker PID controller for angle for the robot.
desiredRotationThe angle that the robot should be facing. This is sampled at every time step.
maxWheelVelocityThe maximum velocity of a drivetrain wheel.
outputThe output of the position PIDs.
requirementsThe subsystems to require.

◆ MecanumControllerCommand() [8/8]

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.

Parameters
trajectoryThe trajectory to follow.
poseA function that supplies the robot pose - use one of the odometry classes to provide this.
kinematicsThe kinematics for the robot drivetrain.
xControllerThe Trajectory Tracker PID controller for the robot's x position.
yControllerThe Trajectory Tracker PID controller for the robot's y position.
thetaControllerThe Trajectory Tracker PID controller for angle for the robot.
maxWheelVelocityThe maximum velocity of a drivetrain wheel.
outputThe output of the position PIDs.
requirementsThe subsystems to require.

Member Function Documentation

◆ End()

void frc2::MecanumControllerCommand::End ( bool  interrupted)
override

◆ Execute()

void frc2::MecanumControllerCommand::Execute ( )
override

◆ Initialize()

void frc2::MecanumControllerCommand::Initialize ( )
override

◆ IsFinished()

bool frc2::MecanumControllerCommand::IsFinished ( )
override

The documentation for this class was generated from the following file: