WPILibC++ 2023.4.3-108-ge5452e3
frc2::SwerveControllerCommand< NumModules > Class Template Reference

A command that uses two PID controllers (PIDController) and a profiled PID controller (ProfiledPIDController) to follow a trajectory (Trajectory) with a swerve drive. More...

#include <frc2/command/SwerveControllerCommand.h>

Inheritance diagram for frc2::SwerveControllerCommand< NumModules >:
frc2::CommandHelper< CommandBase, SwerveControllerCommand< NumModules > >

Public Member Functions

 SwerveControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SwerveDriveKinematics< NumModules > kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, std::function< void(std::array< frc::SwerveModuleState, NumModules >)> output, std::initializer_list< Subsystem * > requirements)
 Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory. More...
 
 SwerveControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SwerveDriveKinematics< NumModules > kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< void(std::array< frc::SwerveModuleState, NumModules >)> output, std::initializer_list< Subsystem * > requirements)
 Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory. More...
 
 SwerveControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SwerveDriveKinematics< NumModules > kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, std::function< void(std::array< frc::SwerveModuleState, NumModules >)> output, std::span< Subsystem *const > requirements={})
 Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory. More...
 
 SwerveControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SwerveDriveKinematics< NumModules > kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< void(std::array< frc::SwerveModuleState, NumModules >)> output, std::span< Subsystem *const > requirements={})
 Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory. More...
 
 SwerveControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SwerveDriveKinematics< NumModules > kinematics, frc::HolonomicDriveController controller, std::function< frc::Rotation2d()> desiredRotation, std::function< void(std::array< frc::SwerveModuleState, NumModules >)> output, std::initializer_list< Subsystem * > requirements)
 Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory. More...
 
 SwerveControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SwerveDriveKinematics< NumModules > kinematics, frc::HolonomicDriveController controller, std::function< void(std::array< frc::SwerveModuleState, NumModules >)> output, std::initializer_list< Subsystem * > requirements)
 Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory. More...
 
 SwerveControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SwerveDriveKinematics< NumModules > kinematics, frc::HolonomicDriveController controller, std::function< frc::Rotation2d()> desiredRotation, std::function< void(std::array< frc::SwerveModuleState, NumModules >)> output, std::span< Subsystem *const > requirements={})
 Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory. More...
 
 SwerveControllerCommand (frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SwerveDriveKinematics< NumModules > kinematics, frc::HolonomicDriveController controller, std::function< void(std::array< frc::SwerveModuleState, NumModules >)> output, std::span< Subsystem *const > requirements={})
 Constructs a new SwerveControllerCommand 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, SwerveControllerCommand< NumModules > >
 CommandHelper ()=default
 
CommandPtr ToPtr () &&override
 

Additional Inherited Members

- Protected Member Functions inherited from frc2::CommandHelper< CommandBase, SwerveControllerCommand< NumModules > >
std::unique_ptr< CommandTransferOwnership () &&override
 

Detailed Description

template<size_t NumModules>
class frc2::SwerveControllerCommand< NumModules >

A command that uses two PID controllers (PIDController) and a profiled PID controller (ProfiledPIDController) to follow a trajectory (Trajectory) with a swerve 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 module states from the position 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

◆ SwerveControllerCommand() [1/8]

template<size_t NumModules>
frc2::SwerveControllerCommand< NumModules >::SwerveControllerCommand ( frc::Trajectory  trajectory,
std::function< frc::Pose2d()>  pose,
frc::SwerveDriveKinematics< NumModules >  kinematics,
frc2::PIDController  xController,
frc2::PIDController  yController,
frc::ProfiledPIDController< units::radians >  thetaController,
std::function< frc::Rotation2d()>  desiredRotation,
std::function< void(std::array< frc::SwerveModuleState, NumModules >)>  output,
std::initializer_list< Subsystem * >  requirements 
)

Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory.

This command will not return output voltages but rather raw module states from the position controllers which need to be put into a velocity PID.

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.
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 drivetrain should be facing. This is sampled at each time step.
outputThe raw output module states from the position controllers.
requirementsThe subsystems to require.

◆ SwerveControllerCommand() [2/8]

template<size_t NumModules>
frc2::SwerveControllerCommand< NumModules >::SwerveControllerCommand ( frc::Trajectory  trajectory,
std::function< frc::Pose2d()>  pose,
frc::SwerveDriveKinematics< NumModules >  kinematics,
frc2::PIDController  xController,
frc2::PIDController  yController,
frc::ProfiledPIDController< units::radians >  thetaController,
std::function< void(std::array< frc::SwerveModuleState, NumModules >)>  output,
std::initializer_list< Subsystem * >  requirements 
)

Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory.

This command will not return output voltages but rather raw module states from the position controllers which need to be put into a velocity PID.

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.
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.
outputThe raw output module states from the position controllers.
requirementsThe subsystems to require.

◆ SwerveControllerCommand() [3/8]

template<size_t NumModules>
frc2::SwerveControllerCommand< NumModules >::SwerveControllerCommand ( frc::Trajectory  trajectory,
std::function< frc::Pose2d()>  pose,
frc::SwerveDriveKinematics< NumModules >  kinematics,
frc2::PIDController  xController,
frc2::PIDController  yController,
frc::ProfiledPIDController< units::radians >  thetaController,
std::function< frc::Rotation2d()>  desiredRotation,
std::function< void(std::array< frc::SwerveModuleState, NumModules >)>  output,
std::span< Subsystem *const >  requirements = {} 
)

Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory.

This command will not return output voltages but rather raw module states from the position controllers which need to be put into a velocity PID.

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.
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 drivetrain should be facing. This is sampled at each time step.
outputThe raw output module states from the position controllers.
requirementsThe subsystems to require.

◆ SwerveControllerCommand() [4/8]

template<size_t NumModules>
frc2::SwerveControllerCommand< NumModules >::SwerveControllerCommand ( frc::Trajectory  trajectory,
std::function< frc::Pose2d()>  pose,
frc::SwerveDriveKinematics< NumModules >  kinematics,
frc2::PIDController  xController,
frc2::PIDController  yController,
frc::ProfiledPIDController< units::radians >  thetaController,
std::function< void(std::array< frc::SwerveModuleState, NumModules >)>  output,
std::span< Subsystem *const >  requirements = {} 
)

Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory.

This command will not return output voltages but rather raw module states from the position controllers which need to be put into a velocity PID.

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.
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.
outputThe raw output module states from the position controllers.
requirementsThe subsystems to require.

◆ SwerveControllerCommand() [5/8]

template<size_t NumModules>
frc2::SwerveControllerCommand< NumModules >::SwerveControllerCommand ( frc::Trajectory  trajectory,
std::function< frc::Pose2d()>  pose,
frc::SwerveDriveKinematics< NumModules >  kinematics,
frc::HolonomicDriveController  controller,
std::function< frc::Rotation2d()>  desiredRotation,
std::function< void(std::array< frc::SwerveModuleState, NumModules >)>  output,
std::initializer_list< Subsystem * >  requirements 
)

Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory.

This command will not return output voltages but rather raw module states from the position controllers which need to be put into a velocity PID.

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.
kinematicsThe kinematics for the robot drivetrain.
controllerThe HolonomicDriveController for the drivetrain.
desiredRotationThe angle that the drivetrain should be facing. This is sampled at each time step.
outputThe raw output module states from the position controllers.
requirementsThe subsystems to require.

◆ SwerveControllerCommand() [6/8]

template<size_t NumModules>
frc2::SwerveControllerCommand< NumModules >::SwerveControllerCommand ( frc::Trajectory  trajectory,
std::function< frc::Pose2d()>  pose,
frc::SwerveDriveKinematics< NumModules >  kinematics,
frc::HolonomicDriveController  controller,
std::function< void(std::array< frc::SwerveModuleState, NumModules >)>  output,
std::initializer_list< Subsystem * >  requirements 
)

Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory.

This command will not return output voltages but rather raw module states from the position controllers which need to be put into a velocity PID.

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.
kinematicsThe kinematics for the robot drivetrain.
controllerThe HolonomicDriveController for the drivetrain.
outputThe raw output module states from the position controllers.
requirementsThe subsystems to require.

◆ SwerveControllerCommand() [7/8]

template<size_t NumModules>
frc2::SwerveControllerCommand< NumModules >::SwerveControllerCommand ( frc::Trajectory  trajectory,
std::function< frc::Pose2d()>  pose,
frc::SwerveDriveKinematics< NumModules >  kinematics,
frc::HolonomicDriveController  controller,
std::function< frc::Rotation2d()>  desiredRotation,
std::function< void(std::array< frc::SwerveModuleState, NumModules >)>  output,
std::span< Subsystem *const >  requirements = {} 
)

Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory.

This command will not return output voltages but rather raw module states from the position controllers which need to be put into a velocity PID.

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.
kinematicsThe kinematics for the robot drivetrain.
controllerThe HolonomicDriveController for the robot.
desiredRotationThe angle that the drivetrain should be facing. This is sampled at each time step.
outputThe raw output module states from the position controllers.
requirementsThe subsystems to require.

◆ SwerveControllerCommand() [8/8]

template<size_t NumModules>
frc2::SwerveControllerCommand< NumModules >::SwerveControllerCommand ( frc::Trajectory  trajectory,
std::function< frc::Pose2d()>  pose,
frc::SwerveDriveKinematics< NumModules >  kinematics,
frc::HolonomicDriveController  controller,
std::function< void(std::array< frc::SwerveModuleState, NumModules >)>  output,
std::span< Subsystem *const >  requirements = {} 
)

Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory.

This command will not return output voltages but rather raw module states from the position controllers which need to be put into a velocity PID.

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.
kinematicsThe kinematics for the robot drivetrain.
controllerThe HolonomicDriveController for the drivetrain.
outputThe raw output module states from the position controllers.
requirementsThe subsystems to require.

Member Function Documentation

◆ End()

template<size_t NumModules>
void frc2::SwerveControllerCommand< NumModules >::End ( bool  interrupted)
override

◆ Execute()

template<size_t NumModules>
void frc2::SwerveControllerCommand< NumModules >::Execute
override

◆ Initialize()

template<size_t NumModules>
void frc2::SwerveControllerCommand< NumModules >::Initialize
override

◆ IsFinished()

template<size_t NumModules>
bool frc2::SwerveControllerCommand< NumModules >::IsFinished
override

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