|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Object lejos.navigation.SimpleNavigator lejos.navigation.WaypointNavigator
public class WaypointNavigator
The WaypointNavigator class extends the SimpleNavigator allowing the specify a path along a set of coordinates.
Constructor Summary | |
---|---|
WaypointNavigator(Pilot pilot,
float x,
float y,
float heading)
Create a WaypointNavigator. |
Method Summary | |
---|---|
void |
add(float xpos,
float ypos,
float turnSpeed,
float moveSpeed)
Add a point to the path to move. |
void |
clear()
Stop the robot and clear the queue. |
void |
execute()
Start to move along the list of points in the queue. |
Methods inherited from class lejos.navigation.SimpleNavigator |
---|
angleTo, backward, distanceTo, forward, getAngle, getPilot, getX, getY, goTo, goTo, isMoving, rotate, rotate, rotateLeft, rotateRight, rotateTo, rotateTo, setMoveSpeed, setPosition, setSpeed, setTurnSpeed, stop, travel, travel, turn, turn, turn, updatePosition |
Methods inherited from class java.lang.Object |
---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
Constructor Detail |
---|
public WaypointNavigator(Pilot pilot, float x, float y, float heading)
pilot
- The Pilot to use.x
- The starting x position.y
- The starting y position.heading
- The starting heading.Method Detail |
---|
public void clear()
public void add(float xpos, float ypos, float turnSpeed, float moveSpeed)
xpos
- The x coordinate.ypos
- The y coordinate.turnSpeed
- The speed to use for turns.moveSpeed
- The speed to use for moves.public void execute()
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |