TrajectoryConfig

class wpimath.trajectory.TrajectoryConfig(maxVelocity: meters_per_second, maxAcceleration: meters_per_second_squared)

Bases: pybind11_object

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.

Constructs a config object.

Parameters:
  • maxVelocity – The max velocity of the trajectory.

  • maxAcceleration – The max acceleration of the trajectory.

addConstraint(constraint: TrajectoryConstraint) None

Adds a user-defined constraint to the trajectory.

Parameters:

constraint – The user-defined constraint.

endVelocity() meters_per_second

Returns the ending velocity of the trajectory.

Returns:

The ending velocity of the trajectory.

static fromFps(maxVelocity: feet_per_second, maxAcceleration: feet_per_second_squared) wpimath._controls._controls.trajectory.TrajectoryConfig
isReversed() bool

Returns whether the trajectory is reversed or not.

Returns:

whether the trajectory is reversed or not.

maxAcceleration() meters_per_second_squared

Returns the maximum acceleration of the trajectory.

Returns:

The maximum acceleration of the trajectory.

maxVelocity() meters_per_second

Returns the maximum velocity of the trajectory.

Returns:

The maximum velocity of the trajectory.

setEndVelocity(endVelocity: meters_per_second) None

Sets the end velocity of the trajectory.

Parameters:

endVelocity – The end velocity of the trajectory.

setKinematics(*args, **kwargs)

Overloaded function.

  1. setKinematics(self: wpimath._controls._controls.trajectory.TrajectoryConfig, kinematics: wpimath.kinematics._kinematics.DifferentialDriveKinematics) -> None

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

Parameters:

kinematics – The differential drive kinematics.

  1. setKinematics(self: wpimath._controls._controls.trajectory.TrajectoryConfig, kinematics: wpimath.kinematics._kinematics.MecanumDriveKinematics) -> None

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

Parameters:

kinematics – The mecanum drive kinematics.

  1. setKinematics(self: wpimath._controls._controls.trajectory.TrajectoryConfig, kinematics: wpimath.kinematics._kinematics.SwerveDrive2Kinematics) -> None

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

Parameters:

kinematics – The swerve drive kinematics.

  1. setKinematics(self: wpimath._controls._controls.trajectory.TrajectoryConfig, kinematics: wpimath.kinematics._kinematics.SwerveDrive3Kinematics) -> None

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

Parameters:

kinematics – The swerve drive kinematics.

  1. setKinematics(self: wpimath._controls._controls.trajectory.TrajectoryConfig, kinematics: wpimath.kinematics._kinematics.SwerveDrive4Kinematics) -> None

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

Parameters:

kinematics – The swerve drive kinematics.

  1. setKinematics(self: wpimath._controls._controls.trajectory.TrajectoryConfig, kinematics: wpimath.kinematics._kinematics.SwerveDrive6Kinematics) -> None

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

Parameters:

kinematics – The swerve drive kinematics.

setReversed(reversed: bool) None

Sets the reversed flag of the trajectory.

Parameters:

reversed – Whether the trajectory should be reversed or not.

setStartVelocity(startVelocity: meters_per_second) None

Sets the start velocity of the trajectory.

Parameters:

startVelocity – The start velocity of the trajectory.

startVelocity() meters_per_second

Returns the starting velocity of the trajectory.

Returns:

The starting velocity of the trajectory.