WPILibC++ 2024.3.2
frc::TrajectoryConfig Class Reference

Represents the configuration for generating a trajectory. More...

#include <frc/trajectory/TrajectoryConfig.h>

Public Member Functions

 TrajectoryConfig (units::meters_per_second_t maxVelocity, units::meters_per_second_squared_t maxAcceleration)
 Constructs a config object. More...
 
 TrajectoryConfig (const TrajectoryConfig &)=delete
 
TrajectoryConfigoperator= (const TrajectoryConfig &)=delete
 
 TrajectoryConfig (TrajectoryConfig &&)=default
 
TrajectoryConfigoperator= (TrajectoryConfig &&)=default
 
void SetStartVelocity (units::meters_per_second_t startVelocity)
 Sets the start velocity of the trajectory. More...
 
void SetEndVelocity (units::meters_per_second_t endVelocity)
 Sets the end velocity of the trajectory. More...
 
void SetReversed (bool reversed)
 Sets the reversed flag of the trajectory. More...
 
template<std::derived_from< TrajectoryConstraint > Constraint>
void AddConstraint (Constraint constraint)
 Adds a user-defined constraint to the trajectory. More...
 
void SetKinematics (const DifferentialDriveKinematics &kinematics)
 Adds a differential drive kinematics constraint to ensure that no wheel velocity of a differential drive goes above the max velocity. More...
 
void SetKinematics (MecanumDriveKinematics kinematics)
 Adds a mecanum drive kinematics constraint to ensure that no wheel velocity of a mecanum drive goes above the max velocity. More...
 
template<size_t NumModules>
void SetKinematics (SwerveDriveKinematics< NumModules > &kinematics)
 Adds a swerve drive kinematics constraint to ensure that no wheel velocity of a swerve drive goes above the max velocity. More...
 
units::meters_per_second_t StartVelocity () const
 Returns the starting velocity of the trajectory. More...
 
units::meters_per_second_t EndVelocity () const
 Returns the ending velocity of the trajectory. More...
 
units::meters_per_second_t MaxVelocity () const
 Returns the maximum velocity of the trajectory. More...
 
units::meters_per_second_squared_t MaxAcceleration () const
 Returns the maximum acceleration of the trajectory. More...
 
const std::vector< std::unique_ptr< TrajectoryConstraint > > & Constraints () const
 Returns the user-defined constraints of the trajectory. More...
 
bool IsReversed () const
 Returns whether the trajectory is reversed or not. More...
 

Detailed Description

Represents the configuration for generating a trajectory.

This class stores the start velocity, end velocity, max velocity, max acceleration, custom constraints, and the reversed flag.

The class must be constructed with a max velocity and max acceleration. The other parameters (start velocity, end velocity, constraints, reversed) have been defaulted to reasonable values (0, 0, {}, false). These values can be changed via the SetXXX methods.

Constructor & Destructor Documentation

◆ TrajectoryConfig() [1/3]

frc::TrajectoryConfig::TrajectoryConfig ( units::meters_per_second_t  maxVelocity,
units::meters_per_second_squared_t  maxAcceleration 
)
inline

Constructs a config object.

Parameters
maxVelocityThe max velocity of the trajectory.
maxAccelerationThe max acceleration of the trajectory.

◆ TrajectoryConfig() [2/3]

frc::TrajectoryConfig::TrajectoryConfig ( const TrajectoryConfig )
delete

◆ TrajectoryConfig() [3/3]

frc::TrajectoryConfig::TrajectoryConfig ( TrajectoryConfig &&  )
default

Member Function Documentation

◆ AddConstraint()

template<std::derived_from< TrajectoryConstraint > Constraint>
void frc::TrajectoryConfig::AddConstraint ( Constraint  constraint)
inline

Adds a user-defined constraint to the trajectory.

Parameters
constraintThe user-defined constraint.

◆ Constraints()

const std::vector< std::unique_ptr< TrajectoryConstraint > > & frc::TrajectoryConfig::Constraints ( ) const
inline

Returns the user-defined constraints of the trajectory.

Returns
The user-defined constraints of the trajectory.

◆ EndVelocity()

units::meters_per_second_t frc::TrajectoryConfig::EndVelocity ( ) const
inline

Returns the ending velocity of the trajectory.

Returns
The ending velocity of the trajectory.

◆ IsReversed()

bool frc::TrajectoryConfig::IsReversed ( ) const
inline

Returns whether the trajectory is reversed or not.

Returns
whether the trajectory is reversed or not.

◆ MaxAcceleration()

units::meters_per_second_squared_t frc::TrajectoryConfig::MaxAcceleration ( ) const
inline

Returns the maximum acceleration of the trajectory.

Returns
The maximum acceleration of the trajectory.

◆ MaxVelocity()

units::meters_per_second_t frc::TrajectoryConfig::MaxVelocity ( ) const
inline

Returns the maximum velocity of the trajectory.

Returns
The maximum velocity of the trajectory.

◆ operator=() [1/2]

TrajectoryConfig & frc::TrajectoryConfig::operator= ( const TrajectoryConfig )
delete

◆ operator=() [2/2]

TrajectoryConfig & frc::TrajectoryConfig::operator= ( TrajectoryConfig &&  )
default

◆ SetEndVelocity()

void frc::TrajectoryConfig::SetEndVelocity ( units::meters_per_second_t  endVelocity)
inline

Sets the end velocity of the trajectory.

Parameters
endVelocityThe end velocity of the trajectory.

◆ SetKinematics() [1/3]

void frc::TrajectoryConfig::SetKinematics ( const DifferentialDriveKinematics kinematics)
inline

Adds a differential drive kinematics constraint to ensure that no wheel velocity of a differential drive goes above the max velocity.

Parameters
kinematicsThe differential drive kinematics.

◆ SetKinematics() [2/3]

void frc::TrajectoryConfig::SetKinematics ( MecanumDriveKinematics  kinematics)
inline

Adds a mecanum drive kinematics constraint to ensure that no wheel velocity of a mecanum drive goes above the max velocity.

Parameters
kinematicsThe mecanum drive kinematics.

◆ SetKinematics() [3/3]

template<size_t NumModules>
void frc::TrajectoryConfig::SetKinematics ( SwerveDriveKinematics< NumModules > &  kinematics)
inline

Adds a swerve drive kinematics constraint to ensure that no wheel velocity of a swerve drive goes above the max velocity.

Parameters
kinematicsThe swerve drive kinematics.

◆ SetReversed()

void frc::TrajectoryConfig::SetReversed ( bool  reversed)
inline

Sets the reversed flag of the trajectory.

Parameters
reversedWhether the trajectory should be reversed or not.

◆ SetStartVelocity()

void frc::TrajectoryConfig::SetStartVelocity ( units::meters_per_second_t  startVelocity)
inline

Sets the start velocity of the trajectory.

Parameters
startVelocityThe start velocity of the trajectory.

◆ StartVelocity()

units::meters_per_second_t frc::TrajectoryConfig::StartVelocity ( ) const
inline

Returns the starting velocity of the trajectory.

Returns
The starting velocity of the trajectory.

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