WPILibC++ 2024.3.2
|
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 | |
TrajectoryConfig & | operator= (const TrajectoryConfig &)=delete |
TrajectoryConfig (TrajectoryConfig &&)=default | |
TrajectoryConfig & | operator= (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... | |
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.
|
inline |
Constructs a config object.
maxVelocity | The max velocity of the trajectory. |
maxAcceleration | The max acceleration of the trajectory. |
|
delete |
|
default |
|
inline |
Adds a user-defined constraint to the trajectory.
constraint | The user-defined constraint. |
|
inline |
Returns the user-defined constraints of the trajectory.
|
inline |
Returns the ending velocity of the trajectory.
|
inline |
Returns whether the trajectory is reversed or not.
|
inline |
Returns the maximum acceleration of the trajectory.
|
inline |
Returns the maximum velocity of the trajectory.
|
delete |
|
default |
|
inline |
Sets the end velocity of the trajectory.
endVelocity | The end velocity of the trajectory. |
|
inline |
Adds a differential drive kinematics constraint to ensure that no wheel velocity of a differential drive goes above the max velocity.
kinematics | The differential drive kinematics. |
|
inline |
Adds a mecanum drive kinematics constraint to ensure that no wheel velocity of a mecanum drive goes above the max velocity.
kinematics | The mecanum drive kinematics. |
|
inline |
Adds a swerve drive kinematics constraint to ensure that no wheel velocity of a swerve drive goes above the max velocity.
kinematics | The swerve drive kinematics. |
|
inline |
Sets the reversed flag of the trajectory.
reversed | Whether the trajectory should be reversed or not. |
|
inline |
Sets the start velocity of the trajectory.
startVelocity | The start velocity of the trajectory. |
|
inline |
Returns the starting velocity of the trajectory.