Class TrcPathBuilder

java.lang.Object
trclib.pathdrive.TrcPathBuilder

public class TrcPathBuilder extends Object
This class builds a TrcPath for path following drive. The path can be built from two types of waypoints: INCREMENTAL_PATH - points in the path are relative to their previous points. REFERENCE_FRAME_PATH - points in the path are in the same reference frame as the starting pose.

For example, in traditional PID drive: If the robot starts at the absolute field position of (x=48.0, y=12.0, heading=0.0) and we would want to specify a path with 3 segments of relative movement: 1. move forward 24 inches. 2. turn left 90 degrees. 3. strafe right 36 inches. At the end, the robot will be at (x=48.0, y=72.0, heading=-90.0).

In INCREMENTAL_PATH mode, we would do: TrcPathBuilder pathBuilder = new TrcPathBuilder(driveBase.getFieldPosition(), true) .append(new TrcPose2D(0.0, 24.0, -90.0)) .append(new TrcPose2D(36.0, 0.0, 0.0));

In REFERENCE_FRAME_PATH mode, we would do: TrcPathBuilder pathBuilder = new TrcPathBuilder(driveBase.getFieldPosition(), false) .append(driveBase.getFieldPosition()) .append(new TrcPose2D(48.0, 36.0, -90.0)) .append(new TrcPose2D(48.0, 72.0, -90.0));
  • Field Details

    • waypointList

      private final ArrayList<TrcWaypoint> waypointList
    • startingPose

      private final TrcPose2D startingPose
    • incrementalPath

      private final boolean incrementalPath
    • inDegrees

      private final boolean inDegrees
  • Constructor Details

    • TrcPathBuilder

      public TrcPathBuilder(TrcPose2D startingPose, boolean incrementalPath, boolean inDegrees)
      Constructor: Create an instance of the object.
      Parameters:
      startingPose - specifies the starting pose at the beginning of the path.
      incrementalPath - specifies true if appending point is relative to the previous point in the path, false if appending point is in the same reference frame as startingPose.
      inDegrees - specifies true if appending points have headings with degree unit, false with radian units.
    • TrcPathBuilder

      public TrcPathBuilder(TrcPose2D startingPose, boolean incrementalPath)
      Constructor: Create an instance of the object.
      Parameters:
      startingPose - specifies the starting pose at the beginning of the path.
      incrementalPath - specifies true if appending point is relative to the previous point in the path, false if appending point is in the same reference frame as startingPose.
  • Method Details

    • append

      public TrcPathBuilder append(TrcWaypoint waypoint)
      Appends the specified waypoint to the path.
      Parameters:
      waypoint - specifies the waypoint to be added to the path. If incrementalPoth is true, waypoint is relative to the previous point, otherwise it is in the same reference frame as startingPose. Note: the waypoint will be modified to be in the reference frame of startingPose.
      Returns:
      this instance.
    • append

      public TrcPathBuilder append(TrcPose2D pose, TrcPose2D velocity)
      Appends the specified pose and velocity to the path.
      Parameters:
      pose - specifies the pose to be added to the path. If incrementalPoth is true, pose is relative to the previous point, otherwise it is in the same reference frame as startingPose.
      velocity - specifies the velocity at the pose.
      Returns:
      this instance.
    • append

      public TrcPathBuilder append(TrcPose2D pose)
      Appends the specified pose to the path.
      Parameters:
      pose - specifies the pose to be added to the path. If incrementalPoth is true, pose is relative to the previous point, otherwise it is in the same reference frame as startingPose.
      Returns:
      this instance.
    • toPath

      public TrcPath toPath()
      This method returns the TrcPath built. All waypoints in the path are in the same reference frame as startingPose. Note: waypoint headings are relative to the field, regardless of reference frame.
      Returns:
      resulting TrcPath.
    • toRelativeStartPath

      public TrcPath toRelativeStartPath()
      This method returns the TrcPath built. All waypoints in the path are relative to startingPose. Note: waypoint headings are relative to the field, regardless of reference frame.
      Returns:
      resulting TrcPath relative to startingPose.