Class MotionProfile

java.lang.Object
org.chsrobotics.lib.trajectory.motionProfile.MotionProfile
Direct Known Subclasses:
AsymmetricTrapezoidProfile

public class MotionProfile extends Object
A group of ProfilePhases that represents an arbitrary trajectory of compound accelerations, coasts, and decelerations.

A motion profile provides a trajectory, most often used as the setpoint for a PID (or similar) controller.

This can be useful to avoid control effort saturation, or to decrease the initial large input from a PID's P term. Can also be useful to remain within physical constraints of a mechanism.

This class only contains constructors out of user-defined and user-calculated phases, but AsymmetricTrapezoidProfile and TrapezoidProfile extend this to create profiles out of constraints and desired states.

  • Constructor Details

    • MotionProfile

      public MotionProfile(MotionProfile.State initialState, ProfilePhase... phases)
      Constructs a MotionProfile with arbitrary phases.
      Parameters:
      initialState - The initial state of the motion profile.
      phases - The ProfilePhases of the motion profile.
    • MotionProfile

      public MotionProfile(ProfilePhase... phases)
      Constructs a MotionProfile of arbitrary phases with an initial state of zero displacement and zero velocity.
      Parameters:
      phases - The ProfilePhases of the profile.
  • Method Details

    • getPhases

      public List<ProfilePhase> getPhases()
      Gets all the phases in the profile.
      Returns:
      An ordered list of ProfilePhases.
    • sample

      public MotionProfile.State sample(double time)
      Calculates the current State of the profile at a given time.

      If the time sampled is less than 0, returns the initial State. If it is greater than the timespan of the profile, returns a State of the aggregated position and zero velocity.

      Parameters:
      time - The time since the beginning of the profile.
      Returns:
      The position and velocity of the profile at that time.
    • totalTime

      public double totalTime()
      Returns the total time needed for the trajectory to finish.
      Returns:
      Total trajectory time.