lejos.robotics.navigation
Interface PathController

All Known Implementing Classes:
NavPathController

public interface PathController

The PathController guides a MoveController to a destination. It can not plan a route, but will navigate to a set of coordinates and possibly avoid obstacles along the way. It uses a collection of waypoints as a queue. The PathController constructor very likely accepts a MoveController and PoseProvider.

Author:
NXJ Team

Method Summary
 void addListener(WayPointListener aListener)
          Adds a WayPointListener that will be notified with the actual waypoint it reached.
 void addTargetListener(WayPointListener targetListener)
          Adds a waypoint listener that will be notified with the theoretical target waypoint it reached.
 void addWayPoint(WayPoint aWayPoint)
          Adds a WayPoint to the route.
 void flushQueue()
          Stops the robot and empties the queue of waypoints (the route)
 void followRoute(Collection<WayPoint> theRoute, boolean immediateReturn)
          Moves the robot through the sequence of waypoints contained in the route.
 MoveController getMoveController()
          Note: There is no corresponding setMoveController() method because the type of robot vehicle could not change after the program starts, unless it was physically a transformer robot.
 PoseProvider getPoseProvider()
          Get a reference to the PoseProvider being used as a localizer.
 void goTo(double x, double y)
          This method causes the robot to travel to a new location.
 void goTo(WayPoint destination)
          This method causes the robot to travel to a new location.
 void goTo(WayPoint destination, boolean immediateReturn)
          This method causes the robot to travel to a new location.
 void interrupt()
          Stops the robot immediately; preserves the rest of the queue
 void resume()
          Resumes following the route
 void setPoseProvider(PoseProvider aProvider)
          Sets a new PoseProvider for the PathController robot to use.
 

Method Detail

goTo

void goTo(WayPoint destination,
          boolean immediateReturn)
This method causes the robot to travel to a new location. If the robot is moving, it stops, the route is emptied and the destination is added to it. The robot then starts moving to the coordinates of the destination WayPoint

Parameters:
destination - the destination MoveController
immediateReturn - true for non-blocking, false for blocking

goTo

void goTo(WayPoint destination)
This method causes the robot to travel to a new location. If the robot is moving, it stops, the route is emptied and the destination is added to it. The robot then starts moving to the coordinates of the destination WayPoint.

Parameters:
destination - the destination waypoint

goTo

void goTo(double x,
          double y)
This method causes the robot to travel to a new location. If the robot is moving, it stops, the route is emptied and the destination is added to it. The robot then starts moving to the coordinates of the destination WayPoint.

Parameters:
x - The x coordinate
y - The y coordinate

followRoute

void followRoute(Collection<WayPoint> theRoute,
                 boolean immediateReturn)
Moves the robot through the sequence of waypoints contained in the route. Informs its listeners of each waypoint reached. The waypoint is removed from the route when it is reached.

Parameters:
theRoute -
immediateReturn - ; if false the method returns when the route is empty

flushQueue

void flushQueue()
Stops the robot and empties the queue of waypoints (the route)


interrupt

void interrupt()
Stops the robot immediately; preserves the rest of the queue


resume

void resume()
Resumes following the route


addWayPoint

void addWayPoint(WayPoint aWayPoint)
Adds a WayPoint to the route. If the route was empty, the robot immediately starts moving toward the Waypoint

Parameters:
aWayPoint -

addListener

void addListener(WayPointListener aListener)
Adds a WayPointListener that will be notified with the actual waypoint it reached.

Parameters:
aListener -

addTargetListener

void addTargetListener(WayPointListener targetListener)
Adds a waypoint listener that will be notified with the theoretical target waypoint it reached.

Parameters:
targetListener -

getMoveController

MoveController getMoveController()
Note: There is no corresponding setMoveController() method because the type of robot vehicle could not change after the program starts, unless it was physically a transformer robot.

Returns:
the MoveController

getPoseProvider

PoseProvider getPoseProvider()
Get a reference to the PoseProvider being used as a localizer.

Returns:
the pose provider

setPoseProvider

void setPoseProvider(PoseProvider aProvider)
Sets a new PoseProvider for the PathController robot to use. Example: If the robot moves from one environment (indoors) to another environment (outdoors) it might want to change to another method of localization if a change in environment is detected.

Parameters:
aProvider - the new PoseProvider