FRC Paradigm Shift #1259
Documentation for the 2021 Robot
frc2::SwerveControllerCommand2< NumModules > Class Template Reference
Inheritance diagram for frc2::SwerveControllerCommand2< NumModules >:

Public Member Functions

 SwerveControllerCommand2 (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)
 
 SwerveControllerCommand2 (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)
 
 SwerveControllerCommand2 (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, wpi::ArrayRef< Subsystem * > requirements={})
 
 SwerveControllerCommand2 (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, wpi::ArrayRef< Subsystem * > requirements={})
 
void Initialize () override
 
void Execute () override
 
void End (bool interrupted) override
 
bool IsFinished () override
 

Private Types

using voltsecondspermeter = units::compound_unit< units::voltage::volt, units::second, units::inverse< units::meter >>
 
using voltsecondssquaredpermeter = units::compound_unit< units::voltage::volt, units::squared< units::second >, units::inverse< units::meter >>
 

Private Attributes

frc::Trajectory m_trajectory
 
std::function< frc::Pose2d()> m_pose
 
frc::SwerveDriveKinematics< NumModules > m_kinematics
 
frc::HolonomicDriveController m_controller
 
std::function< void(std::array< frc::SwerveModuleState, NumModules >)> m_outputStates
 
std::function< frc::Rotation2d()> m_desiredRotation
 
frc2::Timer m_timer
 
units::second_t m_prevTime
 
frc::Rotation2d m_finalRotation
 

Detailed Description

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

A command that uses two PID controllers (PIDController) and a ProfiledPIDController (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.

Definition at line 51 of file SwerveControllerCommand2.h.

Member Typedef Documentation

template<size_t NumModules>
using frc2::SwerveControllerCommand2< NumModules >::voltsecondspermeter = units::compound_unit<units::voltage::volt, units::second, units::inverse<units::meter>>
private

Definition at line 55 of file SwerveControllerCommand2.h.

template<size_t NumModules>
using frc2::SwerveControllerCommand2< NumModules >::voltsecondssquaredpermeter = units::compound_unit<units::voltage::volt, units::squared<units::second>, units::inverse<units::meter>>
private

Definition at line 58 of file SwerveControllerCommand2.h.

Constructor & Destructor Documentation

template<size_t NumModules>
frc2::SwerveControllerCommand2< NumModules >::SwerveControllerCommand2 ( 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 SwerveControllerCommand2 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.
template<size_t NumModules>
frc2::SwerveControllerCommand2< NumModules >::SwerveControllerCommand2 ( 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 SwerveControllerCommand2 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.
template<size_t NumModules>
frc2::SwerveControllerCommand2< NumModules >::SwerveControllerCommand2 ( 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,
wpi::ArrayRef< Subsystem * >  requirements = {} 
)

Constructs a new SwerveControllerCommand2 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.
template<size_t NumModules>
frc2::SwerveControllerCommand2< NumModules >::SwerveControllerCommand2 ( 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,
wpi::ArrayRef< Subsystem * >  requirements = {} 
)

Constructs a new SwerveControllerCommand2 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.

Member Function Documentation

template<size_t NumModules>
void frc2::SwerveControllerCommand2< NumModules >::Initialize ( )
override
template<size_t NumModules>
void frc2::SwerveControllerCommand2< NumModules >::Execute ( )
override
template<size_t NumModules>
void frc2::SwerveControllerCommand2< NumModules >::End ( bool  interrupted)
override
template<size_t NumModules>
bool frc2::SwerveControllerCommand2< NumModules >::IsFinished ( )
override

Member Data Documentation

template<size_t NumModules>
frc::Trajectory frc2::SwerveControllerCommand2< NumModules >::m_trajectory
private

Definition at line 219 of file SwerveControllerCommand2.h.

template<size_t NumModules>
std::function<frc::Pose2d()> frc2::SwerveControllerCommand2< NumModules >::m_pose
private

Definition at line 220 of file SwerveControllerCommand2.h.

template<size_t NumModules>
frc::SwerveDriveKinematics<NumModules> frc2::SwerveControllerCommand2< NumModules >::m_kinematics
private

Definition at line 221 of file SwerveControllerCommand2.h.

template<size_t NumModules>
frc::HolonomicDriveController frc2::SwerveControllerCommand2< NumModules >::m_controller
private

Definition at line 222 of file SwerveControllerCommand2.h.

template<size_t NumModules>
std::function<void(std::array<frc::SwerveModuleState, NumModules>)> frc2::SwerveControllerCommand2< NumModules >::m_outputStates
private

Definition at line 224 of file SwerveControllerCommand2.h.

template<size_t NumModules>
std::function<frc::Rotation2d()> frc2::SwerveControllerCommand2< NumModules >::m_desiredRotation
private

Definition at line 226 of file SwerveControllerCommand2.h.

template<size_t NumModules>
frc2::Timer frc2::SwerveControllerCommand2< NumModules >::m_timer
private

Definition at line 228 of file SwerveControllerCommand2.h.

template<size_t NumModules>
units::second_t frc2::SwerveControllerCommand2< NumModules >::m_prevTime
private

Definition at line 229 of file SwerveControllerCommand2.h.

template<size_t NumModules>
frc::Rotation2d frc2::SwerveControllerCommand2< NumModules >::m_finalRotation
private

Definition at line 230 of file SwerveControllerCommand2.h.


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