Class TrajectoryConfig


  • public class TrajectoryConfig
    extends java.lang.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 Detail

      • TrajectoryConfig

        public TrajectoryConfig​(LightningDrivetrain drivetrain,
                                boolean reversed)
        Constructs the trajectory configuration class.
        Parameters:
        drivetrain - Drivetrain that will be driving the trajectory.
        reversed - If the trajectory should be driven backwards.
      • TrajectoryConfig

        public TrajectoryConfig​(LightningDrivetrain drivetrain)
        Constructs the trajectory configuration class.
        Parameters:
        drivetrain - Drivetrain that will be driving the trajectory.
    • Method Detail

      • addConstraint

        public TrajectoryConfig addConstraint​(TrajectoryConstraint constraint)
        Adds a user-defined constraint to the trajectory.
        Parameters:
        constraint - The user-defined constraint.
        Returns:
        Instance of the current config object.
      • addConstraints

        public TrajectoryConfig addConstraints​(java.util.List<? extends TrajectoryConstraint> constraints)
        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.
      • getStartVelocity

        public double getStartVelocity()
        Returns the starting velocity of the trajectory.
        Returns:
        The starting velocity of the trajectory.
      • setStartVelocity

        public TrajectoryConfig setStartVelocity​(double startVelocityMetersPerSecond)
        Sets the start velocity of the trajectory.
        Parameters:
        startVelocityMetersPerSecond - The start velocity of the trajectory.
        Returns:
        Instance of the current config object.
      • getEndVelocity

        public double getEndVelocity()
        Returns the starting velocity of the trajectory.
        Returns:
        The starting velocity of the trajectory.
      • setEndVelocity

        public TrajectoryConfig setEndVelocity​(double endVelocityMetersPerSecond)
        Sets the end velocity of the trajectory.
        Parameters:
        endVelocityMetersPerSecond - The end velocity of the trajectory.
        Returns:
        Instance of the current config object.
      • getMaxVelocity

        public double getMaxVelocity()
        Returns the maximum velocity of the trajectory.
        Returns:
        The maximum velocity of the trajectory.
      • getMaxAcceleration

        public double getMaxAcceleration()
        Returns the maximum acceleration of the trajectory.
        Returns:
        The maximum acceleration of the trajectory.
      • getConstraints

        public java.util.List<TrajectoryConstraint> getConstraints()
        Returns the user-defined constraints of the trajectory.
        Returns:
        The user-defined constraints of the trajectory.
      • isReversed

        public boolean isReversed()
        Returns whether the trajectory is reversed or not.
        Returns:
        whether the trajectory is reversed or not.
      • setReversed

        public TrajectoryConfig setReversed​(boolean reversed)
        Sets the reversed flag of the trajectory.
        Parameters:
        reversed - Whether the trajectory should be reversed or not.
        Returns:
        Instance of the current config object.