Package trclib.pathdrive
Class TrcWaypoint
java.lang.Object
trclib.pathdrive.TrcWaypoint
This class implements a waypoint. A waypoint specifies a point on a path that consists of a relative time step
relative to the previous point, the x and y components of its position relative to a reference point, the encoder
position, velocity and acceleration at this point.
-
Field Summary
FieldsModifier and TypeFieldDescriptiondouble
double
int
double
private boolean
double
double
-
Constructor Summary
ConstructorsConstructorDescriptionTrcWaypoint
(double[] data) Constructor: Create an instance of the object.TrcWaypoint
(double timeStep, double x, double y, double heading, double position, double velocity, double acceleration, double jerk) Constructor: Create an instance of the object.TrcWaypoint
(double timeStep, TrcPose2D pose, double position, double velocity, double acceleration, double jerk) Constructor: Create an instance of the object.TrcWaypoint
(TrcPose2D pose, TrcPose2D velocity) Constructor: Create an instance of the object from a given 2D pose.TrcWaypoint
(TrcWaypoint other) Copy constructor: Create a copy of the given object. -
Method Summary
Modifier and TypeMethodDescriptionclone()
double
distanceTo
(TrcWaypoint point) This method calculates the distance between this waypoint and the other waypoint.static TrcWaypoint[]
loadPointsFromCsv
(String path, boolean loadFromResources) This method loads waypoint data from a CSV file either on the external file system or attached resources.toString()
This method returns the string containing the information of the waypoint.
-
Field Details
-
index
public int index -
timeStep
public double timeStep -
pose
-
encoderPosition
public double encoderPosition -
velocity
public double velocity -
acceleration
public double acceleration -
jerk
public double jerk -
simpleWaypoint
private boolean simpleWaypoint
-
-
Constructor Details
-
TrcWaypoint
public TrcWaypoint(double timeStep, TrcPose2D pose, double position, double velocity, double acceleration, double jerk) Constructor: Create an instance of the object.- Parameters:
timeStep
- specifies the speed denomination in seconds.pose
- specifies the pose in the path reference frame.position
- specifies the encoder position at this points. (arc length)velocity
- specifies the tangential velocity of the wheel at this point.acceleration
- specifies the tangential acceleration at this point.jerk
- specifies the tangential jerk at this point.
-
TrcWaypoint
public TrcWaypoint(double timeStep, double x, double y, double heading, double position, double velocity, double acceleration, double jerk) Constructor: Create an instance of the object.- Parameters:
timeStep
- specifies the speed denomination in seconds.x
- specifies the x position in the path reference frame.y
- specifies the y position in the path reference frame.heading
- specifies the heading of the robot at this point.position
- specifies the encoder position at this points. (arc length)velocity
- specifies the tangential velocity of the wheel at this point.acceleration
- specifies the tangential acceleration at this point.jerk
- specifies the tangential jerk at this point.
-
TrcWaypoint
public TrcWaypoint(double[] data) Constructor: Create an instance of the object.- Parameters:
data
- specifies an array with 8 elements: timeStep, x, y, heading pos, vel, accel and jerk.- Throws:
ArrayIndexOutOfBoundsException
- if array size is less than 8.
-
TrcWaypoint
Copy constructor: Create a copy of the given object.- Parameters:
other
- specifies the other object to be copied.
-
TrcWaypoint
Constructor: Create an instance of the object from a given 2D pose.- Parameters:
pose
- specifies the position of the way point.velocity
- specifies the velocity of the way point.
-
-
Method Details
-
toString
This method returns the string containing the information of the waypoint. -
clone
-
loadPointsFromCsv
This method loads waypoint data from a CSV file either on the external file system or attached resources.- Parameters:
path
- specifies the file system path or resource name.loadFromResources
- specifies true if the data is from attached resources, false if from file system.- Returns:
- an array of waypoints.
-
getPositionPose
-
distanceTo
This method calculates the distance between this waypoint and the other waypoint.- Parameters:
point
- specifies the other waypoint.- Returns:
- distance to the other waypoint.
-