|
| | TrajectoryConfig (wpi::units::meters_per_second_t maxVelocity, wpi::units::meters_per_second_squared_t maxAcceleration) |
| | Constructs a config object.
|
| | TrajectoryConfig (const TrajectoryConfig &)=delete |
| TrajectoryConfig & | operator= (const TrajectoryConfig &)=delete |
| | TrajectoryConfig (TrajectoryConfig &&)=default |
| TrajectoryConfig & | operator= (TrajectoryConfig &&)=default |
| void | SetStartVelocity (wpi::units::meters_per_second_t startVelocity) |
| | Sets the start velocity of the trajectory.
|
| void | SetEndVelocity (wpi::units::meters_per_second_t endVelocity) |
| | Sets the end velocity of the trajectory.
|
| void | SetReversed (bool reversed) |
| | Sets the reversed flag of the trajectory.
|
| template<std::derived_from< TrajectoryConstraint > Constraint> |
| void | AddConstraint (Constraint constraint) |
| | Adds a user-defined constraint to the trajectory.
|
| 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.
|
| 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.
|
| 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.
|
| wpi::units::meters_per_second_t | StartVelocity () const |
| | Returns the starting velocity of the trajectory.
|
| wpi::units::meters_per_second_t | EndVelocity () const |
| | Returns the ending velocity of the trajectory.
|
| wpi::units::meters_per_second_t | MaxVelocity () const |
| | Returns the maximum velocity of the trajectory.
|
| wpi::units::meters_per_second_squared_t | MaxAcceleration () const |
| | Returns the maximum acceleration of the trajectory.
|
| const std::vector< std::unique_ptr< TrajectoryConstraint > > & | Constraints () const |
| | Returns the user-defined constraints of the trajectory.
|
| bool | IsReversed () const |
| | Returns whether the trajectory is reversed or not.
|
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.