Class Trajectory


  • public class Trajectory
    extends Object
    Represents a time-parameterized trajectory. The trajectory contains of various States that represent the pose, curvature, time elapsed, velocity, and acceleration at that point.
    • Constructor Detail

      • Trajectory

        public Trajectory()
        Constructs an empty trajectory.
      • Trajectory

        public Trajectory​(List<Trajectory.State> states)
        Constructs a trajectory from a vector of states.
        Parameters:
        states - A vector of states.
    • Method Detail

      • getInitialPose

        public Pose2d getInitialPose()
        Returns the initial pose of the trajectory.
        Returns:
        The initial pose of the trajectory.
      • getTotalTimeSeconds

        public double getTotalTimeSeconds()
        Returns the overall duration of the trajectory.
        Returns:
        The duration of the trajectory.
      • sample

        public Trajectory.State sample​(double timeSeconds)
        Sample the trajectory at a point in time.
        Parameters:
        timeSeconds - The point in time since the beginning of the trajectory to sample.
        Returns:
        The state at that point in time.
      • transformBy

        public Trajectory transformBy​(Transform2d transform)
        Transforms all poses in the trajectory by the given transform. This is useful for converting a robot-relative trajectory into a field-relative trajectory. This works with respect to the first pose in the trajectory.
        Parameters:
        transform - The transform to transform the trajectory by.
        Returns:
        The transformed trajectory.
      • relativeTo

        public Trajectory relativeTo​(Pose2d pose)
        Transforms all poses in the trajectory so that they are relative to the given pose. This is useful for converting a field-relative trajectory into a robot-relative trajectory.
        Parameters:
        pose - The pose that is the origin of the coordinate frame that the current trajectory will be transformed into.
        Returns:
        The transformed trajectory.
      • concatenate

        public Trajectory concatenate​(Trajectory other)
        Concatenates another trajectory to the current trajectory. The user is responsible for making sure that the end pose of this trajectory and the start pose of the other trajectory match (if that is the desired behavior).
        Parameters:
        other - The trajectory to concatenate.
        Returns:
        The concatenated trajectory.