WPILibC++ 2023.4.3
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 > > frc2::CommandBase frc2::Command wpi::Sendable wpi::SendableHelper< CommandBase >

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
 The initial subroutine of a command. More...
 
void Execute () override
 The main body of a command. More...
 
void End (bool interrupted) override
 The action to take when the command ends. More...
 
bool IsFinished () override
 Whether the command has finished. More...
 
- Public Member Functions inherited from frc2::CommandHelper< CommandBase, SwerveControllerCommand< NumModules > >
 CommandHelper ()=default
 
CommandPtr ToPtr () &&override
 
- Public Member Functions inherited from frc2::CommandBase
void AddRequirements (std::initializer_list< Subsystem * > requirements)
 Adds the specified Subsystem requirements to the command. More...
 
void AddRequirements (std::span< Subsystem *const > requirements)
 Adds the specified Subsystem requirements to the command. More...
 
void AddRequirements (wpi::SmallSet< Subsystem *, 4 > requirements)
 Adds the specified Subsystem requirements to the command. More...
 
void AddRequirements (Subsystem *requirement)
 Adds the specified Subsystem requirement to the command. More...
 
wpi::SmallSet< Subsystem *, 4 > GetRequirements () const override
 Gets the Subsystem requirements of the command. More...
 
void SetName (std::string_view name) override
 Sets the name of this Command. More...
 
std::string GetName () const override
 Gets the name of this Command. More...
 
std::string GetSubsystem () const
 Gets the subsystem name of this Command. More...
 
void SetSubsystem (std::string_view subsystem)
 Sets the subsystem name of this Command. More...
 
void InitSendable (wpi::SendableBuilder &builder) override
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from frc2::Command
 Command ()=default
 
virtual ~Command ()
 
 Command (const Command &)=default
 
Commandoperator= (const Command &rhs)
 
 Command (Command &&)=default
 
Commandoperator= (Command &&)=default
 
virtual void Initialize ()
 The initial subroutine of a command. More...
 
virtual void Execute ()
 The main body of a command. More...
 
virtual void End (bool interrupted)
 The action to take when the command ends. More...
 
virtual bool IsFinished ()
 Whether the command has finished. More...
 
virtual wpi::SmallSet< Subsystem *, 4 > GetRequirements () const =0
 Specifies the set of subsystems used by this command. More...
 
CommandPtr WithTimeout (units::second_t duration) &&
 Decorates this command with a timeout. More...
 
CommandPtr Until (std::function< bool()> condition) &&
 Decorates this command with an interrupt condition. More...
 
CommandPtr WithInterrupt (std::function< bool()> condition) &&
 Decorates this command with an interrupt condition. More...
 
CommandPtr BeforeStarting (std::function< void()> toRun, std::initializer_list< Subsystem * > requirements) &&
 Decorates this command with a runnable to run before this command starts. More...
 
CommandPtr BeforeStarting (std::function< void()> toRun, std::span< Subsystem *const > requirements={}) &&
 Decorates this command with a runnable to run before this command starts. More...
 
CommandPtr AndThen (std::function< void()> toRun, std::initializer_list< Subsystem * > requirements) &&
 Decorates this command with a runnable to run after the command finishes. More...
 
CommandPtr AndThen (std::function< void()> toRun, std::span< Subsystem *const > requirements={}) &&
 Decorates this command with a runnable to run after the command finishes. More...
 
PerpetualCommand Perpetually () &&
 
CommandPtr Repeatedly () &&
 Decorates this command to run repeatedly, restarting it when it ends, until this command is interrupted. More...
 
CommandPtr AsProxy () &&
 Decorates this command to run "by proxy" by wrapping it in a ProxyCommand. More...
 
CommandPtr Unless (std::function< bool()> condition) &&
 Decorates this command to only run if this condition is not met. More...
 
CommandPtr IgnoringDisable (bool doesRunWhenDisabled) &&
 Decorates this command to run or stop when disabled. More...
 
CommandPtr WithInterruptBehavior (Command::InterruptionBehavior interruptBehavior) &&
 Decorates this command to run or stop when disabled. More...
 
CommandPtr FinallyDo (std::function< void(bool)> end) &&
 Decorates this command with a lambda to call on interrupt or end, following the command's inherent Command::End(bool) method. More...
 
CommandPtr HandleInterrupt (std::function< void()> handler) &&
 Decorates this command with a lambda to call on interrupt, following the command's inherent Command::End(bool) method. More...
 
CommandPtr WithName (std::string_view name) &&
 Decorates this Command with a name. More...
 
void Schedule ()
 Schedules this command. More...
 
void Cancel ()
 Cancels this command. More...
 
bool IsScheduled () const
 Whether or not the command is currently scheduled. More...
 
bool HasRequirement (Subsystem *requirement) const
 Whether the command requires a given subsystem. More...
 
bool IsComposed () const
 Whether the command is currently grouped in a command group. More...
 
void SetComposed (bool isComposed)
 Sets whether the command is currently composed in a command composition. More...
 
bool IsGrouped () const
 Whether the command is currently grouped in a command group. More...
 
void SetGrouped (bool grouped)
 Sets whether the command is currently grouped in a command group. More...
 
virtual bool RunsWhenDisabled () const
 Whether the given command should run when the robot is disabled. More...
 
virtual InterruptionBehavior GetInterruptionBehavior () const
 How the command behaves when another command with a shared requirement is scheduled. More...
 
virtual std::string GetName () const
 Gets the name of this Command. More...
 
virtual void SetName (std::string_view name)
 Sets the name of this Command. More...
 
virtual CommandPtr ToPtr () &&=0
 Transfers ownership of this command to a unique pointer. More...
 
- Public Member Functions inherited from wpi::Sendable
virtual ~Sendable ()=default
 
virtual void InitSendable (SendableBuilder &builder)=0
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from wpi::SendableHelper< CommandBase >
 SendableHelper (const SendableHelper &rhs)=default
 
 SendableHelper (SendableHelper &&rhs)
 
SendableHelperoperator= (const SendableHelper &rhs)=default
 
SendableHelperoperator= (SendableHelper &&rhs)
 

Additional Inherited Members

- Public Types inherited from frc2::Command
enum class  InterruptionBehavior { kCancelSelf , kCancelIncoming }
 An enum describing the command's behavior when another command with a shared requirement is scheduled. More...
 
- Protected Member Functions inherited from frc2::CommandHelper< CommandBase, SwerveControllerCommand< NumModules > >
std::unique_ptr< CommandTransferOwnership () &&override
 
- Protected Member Functions inherited from frc2::CommandBase
 CommandBase ()
 
virtual std::unique_ptr< CommandTransferOwnership () &&=0
 Transfers ownership of this command to a unique pointer. More...
 
- Protected Member Functions inherited from wpi::SendableHelper< CommandBase >
 SendableHelper ()=default
 
 ~SendableHelper ()
 
- Protected Attributes inherited from frc2::CommandBase
wpi::SmallSet< Subsystem *, 4 > m_requirements
 
- Protected Attributes inherited from frc2::Command
bool m_isComposed = false
 

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)
overridevirtual

The action to take when the command ends.

Called when either the command finishes normally, or when it interrupted/canceled.

Parameters
interruptedwhether the command was interrupted/canceled

Reimplemented from frc2::Command.

◆ Execute()

template<size_t NumModules>
void frc2::SwerveControllerCommand< NumModules >::Execute ( )
overridevirtual

The main body of a command.

Called repeatedly while the command is scheduled.

Reimplemented from frc2::Command.

◆ Initialize()

template<size_t NumModules>
void frc2::SwerveControllerCommand< NumModules >::Initialize ( )
overridevirtual

The initial subroutine of a command.

Called once when the command is initially scheduled.

Reimplemented from frc2::Command.

◆ IsFinished()

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

Whether the command has finished.

Once a command finishes, the scheduler will call its end() method and un-schedule it.

Returns
whether the command has finished.

Reimplemented from frc2::Command.


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