Package edu.wpi.first.math.trajectory
Class TrajectoryConfig
java.lang.Object
edu.wpi.first.math.trajectory.TrajectoryConfig
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 Summary
ConstructorDescriptionTrajectoryConfig
(double maxVelocityMetersPerSecond, double maxAccelerationMetersPerSecondSq) Constructs the trajectory configuration class.TrajectoryConfig
(LinearVelocity maxVelocity, LinearAcceleration maxAcceleration) Constructs the trajectory configuration class. -
Method Summary
Modifier and TypeMethodDescriptionaddConstraint
(TrajectoryConstraint constraint) Adds a user-defined constraint to the trajectory.addConstraints
(List<? extends TrajectoryConstraint> constraints) Adds all user-defined constraints from a list to the trajectory.Returns the user-defined constraints of the trajectory.double
Returns the starting velocity of the trajectory.double
Returns the maximum acceleration of the trajectory.double
Returns the maximum velocity of the trajectory.double
Returns the starting velocity of the trajectory.boolean
Returns whether the trajectory is reversed or not.setEndVelocity
(double endVelocityMetersPerSecond) Sets the end velocity of the trajectory.setEndVelocity
(LinearVelocity endVelocity) Sets the end velocity of the trajectory.setKinematics
(DifferentialDriveKinematics kinematics) Adds a differential drive kinematics constraint to ensure that no wheel velocity of a differential drive goes above the max velocity.setKinematics
(MecanumDriveKinematics kinematics) Adds a mecanum drive kinematics constraint to ensure that no wheel velocity of a mecanum drive goes above the max velocity.setKinematics
(SwerveDriveKinematics kinematics) Adds a swerve drive kinematics constraint to ensure that no wheel velocity of a swerve drive goes above the max velocity.setReversed
(boolean reversed) Sets the reversed flag of the trajectory.setStartVelocity
(double startVelocityMetersPerSecond) Sets the start velocity of the trajectory.setStartVelocity
(LinearVelocity startVelocity) Sets the start velocity of the trajectory.
-
Constructor Details
-
TrajectoryConfig
Constructs the trajectory configuration class.- Parameters:
maxVelocityMetersPerSecond
- The max velocity for the trajectory.maxAccelerationMetersPerSecondSq
- The max acceleration for the trajectory.
-
TrajectoryConfig
Constructs the trajectory configuration class.- Parameters:
maxVelocity
- The max velocity for the trajectory.maxAcceleration
- The max acceleration for the trajectory.
-
-
Method Details
-
addConstraint
Adds a user-defined constraint to the trajectory.- Parameters:
constraint
- The user-defined constraint.- Returns:
- Instance of the current config object.
-
addConstraints
Adds all user-defined constraints from a list to the trajectory.- Parameters:
constraints
- List of user-defined constraints.- Returns:
- Instance of the current config object.
-
setKinematics
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.- Returns:
- Instance of the current config object.
-
setKinematics
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.- Returns:
- Instance of the current config object.
-
setKinematics
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.- Returns:
- Instance of the current config object.
-
getStartVelocity
Returns the starting velocity of the trajectory.- Returns:
- The starting velocity of the trajectory.
-
setStartVelocity
Sets the start velocity of the trajectory.- Parameters:
startVelocityMetersPerSecond
- The start velocity of the trajectory.- Returns:
- Instance of the current config object.
-
setStartVelocity
Sets the start velocity of the trajectory.- Parameters:
startVelocity
- The start velocity of the trajectory.- Returns:
- Instance of the current config object.
-
getEndVelocity
Returns the starting velocity of the trajectory.- Returns:
- The starting velocity of the trajectory.
-
setEndVelocity
Sets the end velocity of the trajectory.- Parameters:
endVelocityMetersPerSecond
- The end velocity of the trajectory.- Returns:
- Instance of the current config object.
-
setEndVelocity
Sets the end velocity of the trajectory.- Parameters:
endVelocity
- The end velocity of the trajectory.- Returns:
- Instance of the current config object.
-
getMaxVelocity
Returns the maximum velocity of the trajectory.- Returns:
- The maximum velocity of the trajectory.
-
getMaxAcceleration
Returns the maximum acceleration of the trajectory.- Returns:
- The maximum acceleration of the trajectory.
-
getConstraints
Returns the user-defined constraints of the trajectory.- Returns:
- The user-defined constraints of the trajectory.
-
isReversed
Returns whether the trajectory is reversed or not.- Returns:
- whether the trajectory is reversed or not.
-
setReversed
Sets the reversed flag of the trajectory.- Parameters:
reversed
- Whether the trajectory should be reversed or not.- Returns:
- Instance of the current config object.
-