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