A B C D E F G H I K L M N O P Q R S T U V W X Y _ 

A

addDetector(FeatureDetector) - Method in class lejos.robotics.objectdetection.FusorDetector
This method adds another FeatureDetector to the FusorDetector.
addListener(WaypointListener) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
addListener(WaypointListener) - Method in class lejos.robotics.pathfinding.NodePathFinder
 
addListener(WaypointListener) - Method in interface lejos.robotics.pathfinding.PathFinder
 
addListener(WaypointListener) - Method in class lejos.robotics.pathfinding.RandomPathFinder
 
addListener(WaypointListener) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
addListener(FeatureListener) - Method in interface lejos.robotics.objectdetection.FeatureDetector
Adds a listener to the FeatureDetector.
addListener(FeatureListener) - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
addListener(FeatureListener) - Method in class lejos.robotics.objectdetection.FusorDetector
 
addMoveListener(MoveListener) - Method in class lejos.robotics.navigation.DifferentialPilot
 
addMoveListener(MoveListener) - Method in interface lejos.robotics.navigation.MoveProvider
Adds a MoveListener that will be notified of all movement events.
addNavigationListener(NavigationListener) - Method in class lejos.robotics.navigation.Navigator
Adds a NavigationListener that is informed when a the robot stops or reaches a WayPoint.
addNeighbor(Node) - Method in class lejos.robotics.pathfinding.Node
Adds a neighboring node to this node, connecting them together.
addNode(Node, int) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
Adds a node to this set and connects it with a number of neighboring nodes.
addNode(Node, int) - Method in interface lejos.robotics.pathfinding.NavigationMesh
Adds a node to this set and connects it with a number of neighboring nodes.
addWaypoint(float, float) - Method in class lejos.robotics.navigation.Navigator
Constructs an new Waypoint from the parameters and adds it to the end of the path.
addWaypoint(float, float, float) - Method in class lejos.robotics.navigation.Navigator
Constructs an new Waypoint from the parameters and adds it to the end of the path.
addWaypoint(Waypoint) - Method in class lejos.robotics.navigation.Navigator
Adds a Waypoint to the end of the path.
addWaypoint(Waypoint) - Method in interface lejos.robotics.navigation.WaypointListener
Called when the class providing waypoints generates a new waypoint.
alg - Variable in class lejos.robotics.pathfinding.NodePathFinder
 
angle - Variable in class lejos.robotics.objectdetection.RangeFeatureDetector
 
angle - Variable in class lejos.robotics.objectdetection.TouchFeatureDetector
 
angle0 - Variable in class lejos.robotics.localization.OdometryPoseProvider
 
angleNoiseFactor - Variable in class lejos.robotics.localization.MCLParticleSet
 
angleTo(Point) - Method in class lejos.robotics.navigation.Pose
Returns the angle with respect to the X axis to
angleTurned - Variable in class lejos.robotics.navigation.Move
 
applyMove(Move) - Method in class lejos.robotics.localization.MCLParticleSet
Apply a move to each particle
applyMove(Move, float, float) - Method in class lejos.robotics.localization.MCLParticle
Apply the robot's move to the particle with a bit of random noise.
arc(double, double) - Method in interface lejos.robotics.navigation.ArcMoveController
Moves the NXT robot along an arc with a specified radius and angle, after which the robot stops moving.
arc(double, double) - Method in class lejos.robotics.navigation.DifferentialPilot
 
arc(double, double, boolean) - Method in interface lejos.robotics.navigation.ArcMoveController
Moves the NXT robot along an arc with a specified radius and angle, after which the robot stops moving.
arc(double, double, boolean) - Method in class lejos.robotics.navigation.DifferentialPilot
 
ArcAlgorithms - Class in lejos.robotics.navigation
The static methods in this class can be used to to calculate theoretical routes and for displaying graphical representations of the path of a robot.
ArcAlgorithms() - Constructor for class lejos.robotics.navigation.ArcAlgorithms
 
arcBackward(double) - Method in interface lejos.robotics.navigation.ArcMoveController
Starts the NXT robot moving backward along an arc with a specified radius.
arcBackward(double) - Method in class lejos.robotics.navigation.DifferentialPilot
 
arcForward(double) - Method in interface lejos.robotics.navigation.ArcMoveController
Starts the NXT robot moving forward along an arc with a specified radius.
arcForward(double) - Method in class lejos.robotics.navigation.DifferentialPilot
 
ArcMoveController - Interface in lejos.robotics.navigation
An enhanced MoveController that is capable of traveling in arcs.
arcRadius - Variable in class lejos.robotics.navigation.Move
 
ArcRotateMoveController - Interface in lejos.robotics.navigation
A MoveController for robots that can perform arcs and rotate on the spot.
arcUpdate(float, float) - Method in class lejos.robotics.navigation.Pose
Sets the pose location and heading to the correct values resulting from travel in a circular arc.
AstarSearchAlgorithm - Class in lejos.robotics.pathfinding
This is an implementation of the A* search algorithm.
AstarSearchAlgorithm() - Constructor for class lejos.robotics.pathfinding.AstarSearchAlgorithm
 
atan(double) - Static method in class lejos.robotics.localization.BeaconTriangle
 
atEndOfLine(Line) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
test if this Node is one of the ends of theLine
atEndOfLine(Line) - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
test if this Node is one of the ends of theLine
atWaypoint(Waypoint, Pose, int) - Method in interface lejos.robotics.navigation.NavigationListener
Called when the robot has reached a new Wahpoint.

B

backward() - Method in class lejos.robotics.navigation.DifferentialPilot
Starts the NXT robot moving backward.
backward() - Method in interface lejos.robotics.navigation.MoveController
Starts the NXT robot moving backwards.
bak() - Method in class lejos.robotics.navigation.DifferentialPilot
Motors backward.
beacon1 - Variable in class lejos.robotics.localization.BeaconTriangle
 
beacon2 - Variable in class lejos.robotics.localization.BeaconTriangle
 
beacon3 - Variable in class lejos.robotics.localization.BeaconTriangle
 
BeaconLocator - Interface in lejos.robotics.localization
A class that scans a room for beacons and identifies the angles to the beacons.
BeaconPoseProvider - Class in lejos.robotics.localization
A PoseProvider that uses beacon triangulation to pinpoint the pose (x, y, heading) of a robot.
BeaconPoseProvider(BeaconLocator, BeaconTriangle, MoveProvider) - Constructor for class lejos.robotics.localization.BeaconPoseProvider
Creates a PoseProvider using beacons.
BeaconPoseProvider(BeaconLocator, BeaconTriangle, MoveProvider, int) - Constructor for class lejos.robotics.localization.BeaconPoseProvider
Creates a PoseProvider using beacons.
BeaconTriangle - Class in lejos.robotics.localization
This class represents three beacons in a triangle.
BeaconTriangle(Point, Point, Point) - Constructor for class lejos.robotics.localization.BeaconTriangle
 
betweenAngles(double, double) - Static method in class lejos.robotics.localization.BeaconPoseProvider
Subtracts two angles in a clockwise direction.
BIG - Static variable in class lejos.robotics.pathfinding.DijkstraPathFinder
 
BIG - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
BIG - Static variable in class lejos.robotics.pathfinding.ShortestPathFinder
 
BIG_FLOAT - Static variable in class lejos.robotics.localization.MCLParticleSet
 
BIG_FLOAT - Variable in class lejos.robotics.localization.MCLPoseProvider
 
bl - Variable in class lejos.robotics.localization.BeaconPoseProvider
 
block(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
add aNode to list of nodes not a neighbour of this Node
block(ShortestPathFinder.Node) - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
add aNode to list of nodes that are not a neighbour of this Node
border - Variable in class lejos.robotics.localization.MCLParticleSet
 
border - Variable in class lejos.robotics.localization.MCLPoseProvider
 
boundingRect - Variable in class lejos.robotics.localization.MCLParticleSet
 
boundingRect - Variable in class lejos.robotics.mapping.LineMap
 
bt - Variable in class lejos.robotics.localization.BeaconPoseProvider
 
busy - Variable in class lejos.robotics.localization.MCLPoseProvider
 

C

calcMoveType(float, float) - Static method in class lejos.robotics.navigation.Move
Helper method to calculate the MoveType based on distance, angle, radius parameters.
calcPose(double, double, double) - Method in class lejos.robotics.localization.BeaconTriangle
Triangulates the pose of a robot given three angles to the three beacons.
calculateG(Node) - Method in class lejos.robotics.pathfinding.GridNode
 
calculateG(Node) - Method in class lejos.robotics.pathfinding.Node
Calculates the distance to a neighbor node.
calculateH(Node) - Method in class lejos.robotics.pathfinding.GridNode
 
calculateH(Node) - Method in class lejos.robotics.pathfinding.Node
Calculates the distance to the goal node.
calculateWeight(RangeReadings, RangeMap, float) - Method in class lejos.robotics.localization.MCLParticle
Calculate the weight for this particle by comparing its readings with the robot's readings
calculateWeights(RangeReadings, RangeMap) - Method in class lejos.robotics.localization.MCLParticleSet
Calculate the weight for each particle
calibrate() - Method in class lejos.robotics.navigation.CompassPilot
Rotates the robot 360 degrees while calibrating the compass resets compass zero to heading at end of calibration
callListeners() - Method in class lejos.robotics.navigation.Navigator
 
cameFrom - Variable in class lejos.robotics.pathfinding.Node
The predecessor node used by A* search algorithm to mark off the previous node in the search tree.
cells - Variable in class lejos.robotics.mapping.OccupancyGridMap
 
checkValidity(Pose) - Method in class lejos.robotics.navigation.Waypoint
Check that the given pose satisfies the conditions for this way point
clearance - Variable in class lejos.robotics.pathfinding.FourWayGridMesh
 
clearance - Variable in class lejos.robotics.pathfinding.RandomPathFinder
 
clearPath() - Method in class lejos.robotics.navigation.Navigator
Clears the current path.
compass - Variable in class lejos.robotics.localization.CompassPoseProvider
 
compass - Variable in class lejos.robotics.navigation.CompassPilot
 
CompassPilot - Class in lejos.robotics.navigation
A Pilot that keeps track of direction using a DirectionFinder.
CompassPilot(DirectionFinder, float, float, RegulatedMotor, RegulatedMotor) - Constructor for class lejos.robotics.navigation.CompassPilot
Allocates a CompasPilot object, and sets the physical parameters of the NXT robot.
CompassPilot(DirectionFinder, float, float, RegulatedMotor, RegulatedMotor, boolean) - Constructor for class lejos.robotics.navigation.CompassPilot
Allocates a CompasPilot object, and sets the physical parameters of the NXT robot.
CompassPilot.Regulator - Class in lejos.robotics.navigation
inner class to regulate heading during travel move Proportional control of steering ; error is an average of heading change from tacho counts and from compass change
CompassPoseProvider - Class in lejos.robotics.localization
Pose Provider using a compass (or other direction finder) to provide location and heading data.
CompassPoseProvider(MoveProvider, DirectionFinder) - Constructor for class lejos.robotics.localization.CompassPoseProvider
 
connect(Node, Node) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
 
connect(Node, Node) - Method in interface lejos.robotics.pathfinding.NavigationMesh
Attempts to connect two nodes together by adding them as neighbors.
connections - Variable in class lejos.robotics.pathfinding.RandomSelfGeneratingNode
 
convertAngleToDistance(float, float) - Static method in class lejos.robotics.navigation.Move
Static utility method for converting angle (given turn radius) into distance.
convertDistanceToAngle(float, float) - Static method in class lejos.robotics.navigation.Move
Static utility method for converting distance (given turn radius) into angle.
convertToRelative(double, double) - Static method in class lejos.robotics.localization.BeaconPoseProvider
Converts the absolute Cartesian heading into the relative angle values the robot sees when scanning.
cos(double) - Static method in class lejos.robotics.localization.BeaconTriangle
 
createSVGFile(String) - Method in class lejos.robotics.mapping.LineMap
Create an SVG map file
current - Variable in class lejos.robotics.localization.OdometryPoseProvider
 

D

data_is - Variable in class lejos.robotics.mapping.ShapefileLoader
 
debug - Static variable in class lejos.robotics.localization.MCLParticle
 
debug - Static variable in class lejos.robotics.localization.MCLParticleSet
 
debug - Variable in class lejos.robotics.localization.MCLPoseProvider
 
delay - Variable in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
delay - Variable in class lejos.robotics.objectdetection.FusorDetector
The delay (in ms) between notifying listeners of detected features (if any are detected).
DELAY - Static variable in class lejos.robotics.objectdetection.TouchFeatureDetector
 
DestinationUnreachableException - Exception in lejos.robotics.navigation
Exception thrown by path finders when the destination cannot be reached
DestinationUnreachableException() - Constructor for exception lejos.robotics.navigation.DestinationUnreachableException
 
detectors - Variable in class lejos.robotics.objectdetection.FusorDetector
 
DifferentialPilot - Class in lejos.robotics.navigation
The DifferentialPilot class is a software abstraction of the Pilot mechanism of a NXT robot.
DifferentialPilot(double, double, double, RegulatedMotor, RegulatedMotor, boolean) - Constructor for class lejos.robotics.navigation.DifferentialPilot
Allocates a DifferentialPilot object, and sets the physical parameters of the NXT robot.
DifferentialPilot(double, double, RegulatedMotor, RegulatedMotor) - Constructor for class lejos.robotics.navigation.DifferentialPilot
Allocates a DifferentialPilot object, and sets the physical parameters of the NXT robot.
Assumes Motor.forward() causes the robot to move forward.
DifferentialPilot(double, double, RegulatedMotor, RegulatedMotor, boolean) - Constructor for class lejos.robotics.navigation.DifferentialPilot
Allocates a DifferentialPilot object, and sets the physical parameters of the NXT robot.
DifferentialPilot.Monitor - Class in lejos.robotics.navigation
 
DijkstraPathFinder - Class in lejos.robotics.pathfinding
This class calculates the shortest path from a starting point to a finish point.
DijkstraPathFinder(LineMap) - Constructor for class lejos.robotics.pathfinding.DijkstraPathFinder
 
DijkstraPathFinder.Node - Class in lejos.robotics.pathfinding
 
disconnect(Node, Node) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
 
disconnect(Node, Node) - Method in interface lejos.robotics.pathfinding.NavigationMesh
Disconnects two nodes by removing them as neighbors.
distance - Variable in class lejos.robotics.localization.BeaconPoseProvider
 
distance0 - Variable in class lejos.robotics.localization.OdometryPoseProvider
 
distanceNoiseFactor - Variable in class lejos.robotics.localization.MCLParticleSet
 
distanceTo(Point) - Method in class lejos.robotics.navigation.Pose
Return the distance to the destination
distanceTraveled - Variable in class lejos.robotics.navigation.Move
 
distBetweenPoints(Point, Point) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Calculates the distance between any two points.
distP2toP3(double, double) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Assume p2 is the "takeoff" point and p3 is the final target point, this private helper method is used to calculate the distance between p2 to p3, given only the radius and an intermediate value z.
dumpClosest(RangeReadings, DataOutputStream, float, float) - Method in class lejos.robotics.localization.MCLParticleSet
Find the closest particle to specified coordinates and dump its details to a data output stream.
dumpObject(DataOutputStream) - Method in class lejos.robotics.localization.MCLParticleSet
Serialize the particle set to a data output stream
dumpObject(DataOutputStream) - Method in class lejos.robotics.localization.MCLPoseProvider
Dump the serialized estimate of pose to a data output stream
dumpObject(DataOutputStream) - Method in class lejos.robotics.mapping.LineMap
Dump the map to a DataOutputStream
dumpObject(DataOutputStream) - Method in class lejos.robotics.navigation.Move
 
dumpObject(DataOutputStream) - Method in class lejos.robotics.navigation.Pose
 
dumpObject(DataOutputStream) - Method in class lejos.robotics.navigation.Waypoint
 
dumpObject(DataOutputStream) - Method in class lejos.robotics.objectdetection.RangeFeature
 
dumpObject(DataOutputStream) - Method in class lejos.robotics.pathfinding.Path
 

E

enabled - Variable in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
enabled - Variable in class lejos.robotics.objectdetection.FusorDetector
 
enableDetection(boolean) - Method in interface lejos.robotics.objectdetection.FeatureDetector
Enable or disable detection of objects.
enableDetection(boolean) - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
enableDetection(boolean) - Method in class lejos.robotics.objectdetection.FusorDetector
This method enables/disables automatic scanning and listener reporting for this object and all FeatureDetectors used in this FusorDetector object.
equals(ShortestPathFinder.Node) - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
estimatePose() - Method in class lejos.robotics.localization.MCLPoseProvider
Estimate pose from weighted average of the particles Calculate statistics
events - Variable in class lejos.robotics.localization.MCLPoseProvider.Updater
 

F

Feature - Interface in lejos.robotics.objectdetection
A Feature is an interface for information retrieved about an object detected by sensors.
featureDetected(Feature, FeatureDetector) - Method in interface lejos.robotics.objectdetection.FeatureListener
The angle and range (in a RangeReading) of a feature is reported when a feature is detected.
featureDetected(Feature, FeatureDetector) - Method in class lejos.robotics.objectdetection.FusorDetector
This method must deal with different delays from different sensors.
FeatureDetector - Interface in lejos.robotics.objectdetection
A FeatureDetector is capable of detecting objects and notifying listeners when it detects something.
FeatureDetectorAdapter - Class in lejos.robotics.objectdetection
An adapter to make it easier to implement FeatureDetector classes.
FeatureDetectorAdapter(int) - Constructor for class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
FeatureDetectorAdapter.MonitorThread - Class in lejos.robotics.objectdetection
Thread to monitor the range finder.
FeatureListener - Interface in lejos.robotics.objectdetection
Any class implementing this interface and registering with a FeatureDetector will receive notifications when a feature is detected.
fetchSample(float[], int) - Method in class lejos.robotics.localization.OdometryPoseProvider
 
findCircleCenter(Point, float, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Calculates the center of a circle that rests on the tangent of the vehicle's starting heading.
findClosest(float, float) - Method in class lejos.robotics.localization.MCLParticleSet
Find the index of the particle closest to a given co-ordinates.
findP2(Point, Point, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
This method finds P2 if the vehicle is traveling to a point (with no heading).
findPath(Point, Point, ArrayList<Line>) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
finds the shortest path between start and finish Points whild avoiding the obstacles in the map
findPath(Point, Point, ArrayList<Line>) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
Finds the shortest path between start and finish Points while avoiding the obstacles represented by lines in the map
findPath(Node, Node) - Method in class lejos.robotics.pathfinding.AstarSearchAlgorithm
 
findPath(Node, Node) - Method in interface lejos.robotics.pathfinding.SearchAlgorithm
Method accepts a start node and a goal node, and returns a path consisting of a collection of waypoints which includes the startNode coordinates as the first waypoint, and the goal node coordinates as the final waypoint.
findPointOnHeading(Point, float, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Given a starting point and heading, this method will calculate another Point that is distance away from the first point.
findRoute(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
Finds the shortest path from start to finish using the map (or collection of lines) in the constructor.
findRoute(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.NodePathFinder
 
findRoute(Pose, Waypoint) - Method in interface lejos.robotics.pathfinding.PathFinder
 
findRoute(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.RandomPathFinder
 
findRoute(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
Finds the shortest path from start to finish using the map (or collection of lines) in the constructor.
findRoute(Pose, Waypoint, LineMap) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
Finds the shortest path from start to finish using the map (or collection of lines) in the constructor.
findRoute(Pose, Waypoint, LineMap) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
Finds the shortest path from start to finish using the map ( collection of lines) in the constructor.
firstCall - Variable in class lejos.robotics.pathfinding.RandomSelfGeneratingNode
firstCall indicates if getNeighbors() has been called yet.
flip() - Method in class lejos.robotics.mapping.LineMap
Create a line map with the y axis flipped
followPath() - Method in class lejos.robotics.navigation.Navigator
Starts the robot traversing the current path.
followPath(Path) - Method in class lejos.robotics.navigation.Navigator
Starts the robot traversing the path.
format - Static variable in class lejos.robotics.navigation.Pose
 
forward() - Method in class lejos.robotics.navigation.DifferentialPilot
Starts the NXT robot moving forward.
forward() - Method in interface lejos.robotics.navigation.MoveController
Starts the NXT robot moving forward.
FourWayGridMesh - Class in lejos.robotics.pathfinding
Generates a grid of nodes.
FourWayGridMesh(LineMap, float, float) - Constructor for class lejos.robotics.pathfinding.FourWayGridMesh
Instantiates a grid mesh of nodes which won't interconnect between any map geometry.
freeThreshold - Variable in class lejos.robotics.mapping.OccupancyGridMap
 
FusorDetector - Class in lejos.robotics.objectdetection
If you have a robot with multiple sensors (touch and range) and would like them to report to one listener, or if you want to control them at the same time (such as disabling them all at once) you can use this class.
FusorDetector() - Constructor for class lejos.robotics.objectdetection.FusorDetector
 
FusorDetector.NotifyThread - Class in lejos.robotics.objectdetection
Thread to periodically notify listeners.
fwd() - Method in class lejos.robotics.navigation.DifferentialPilot
Motors forward.

G

g_score - Variable in class lejos.robotics.pathfinding.Node
The cumulative distance from the start node to this node.
generateParticle() - Method in class lejos.robotics.localization.MCLParticleSet
Generate a random particle within the mapped area.
generateParticles() - Method in class lejos.robotics.localization.MCLPoseProvider
Generate a new particle set, uniformly distributed within the map, and uniformly distributed heading.
generatePose() - Method in class lejos.robotics.pathfinding.RandomPathFinder
Generate a random pose within the mapped area, not too close to the edge
getAngleIncrement() - Method in class lejos.robotics.navigation.CompassPilot
Returns the change in robot heading since the last call of reset() normalized to be within -180 and _180 degrees
getAngleIncrement() - Method in class lejos.robotics.navigation.DifferentialPilot
 
getAngleTurned() - Method in class lejos.robotics.navigation.Move
Get the angle turned by a rotate or an arc operation.
getAngularAcceleration() - Method in class lejos.robotics.navigation.DifferentialPilot
 
getAngularAcceleration() - Method in interface lejos.robotics.navigation.RotateMoveController
Returns the acceleration at which the robot accelerates at the start of a move and decelerates at the end of a move.
getAngularSpeed() - Method in class lejos.robotics.navigation.DifferentialPilot
 
getAngularSpeed() - Method in interface lejos.robotics.navigation.RotateMoveController
Returns the value of the rotation speed
getArc(Point, Point, float, float, boolean) - Static method in class lejos.robotics.navigation.ArcAlgorithms
If p1 is the starting point of the robot, and p2 is the point at which the robot is pointing directly at the target point, this method calculates the angle to travel along the circle (an arc) to get from p1 to p2.
getArcBackward(float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Quick calculation of reverse arc instead of going through getArcLength() math again.
getArcOld(Point, Point, double) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Deprecated.
This method is no longer used because it can't calculate >180 angles. Delete any time.
getArcRadius() - Method in class lejos.robotics.navigation.Move
Get the radius of the arc
getAvailablePaths(Pose, float, Pose, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
This method gets all the available paths given a start Pose and destination Post.
getAvailablePaths(Pose, Point, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
This method calculates the moves needed to drive from a starting Pose to a final Point.
getBest(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
Helper method for findPath()
returns the node in the Reached set, whose distance from the start node plus its straight line distance to the destination is the minimum.
getBestPath(Move[][]) - Static method in class lejos.robotics.navigation.ArcAlgorithms
This helper method accepts a number of paths (an array of Move) and selects the shortest path.
getBestPath(Pose, float, Pose, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Find the shortest path for a steering vehicle between two points.
getBestPath(Pose, Point, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
This method generates the shortest path from a starting Pose to a final Point.
getBorder() - Method in class lejos.robotics.localization.MCLParticleSet
Get the border where particles should not be generated
getBoundingRect() - Method in class lejos.robotics.mapping.LineMap
Return the bounding rectangle of the mapped area
getBoundingRect() - Method in interface lejos.robotics.mapping.RangeMap
Get the bounding rectangle for the mapped area
getCompass() - Method in class lejos.robotics.navigation.CompassPilot
Return the compass
getCompassHeading() - Method in class lejos.robotics.navigation.CompassPilot
Method returns the current compass heading
getDelay() - Method in interface lejos.robotics.objectdetection.FeatureDetector
The minimum delay between notification of readings from the feature detector.
getDelay() - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
getDelay() - Method in class lejos.robotics.objectdetection.FusorDetector
 
getDistance(Point) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
get the straight line distance from this node to aPoint
getDistance(Point) - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
Get the straight line distance from this node to aPoint
getDistanceTraveled() - Method in class lejos.robotics.navigation.Move
Get the distance traveled.
getErrorRect() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the minimum rectangle enclosing all the particles
getEstimatedPose() - Method in class lejos.robotics.localization.MCLPoseProvider
 
getF_Score() - Method in class lejos.robotics.pathfinding.Node
Method used by A* to calculate search score.
getFreeThreshold() - Method in class lejos.robotics.mapping.OccupancyGridMap
 
getG_Score() - Method in class lejos.robotics.pathfinding.Node
Method used by A* to calculate search score.
getHeading() - Method in class lejos.robotics.navigation.CompassPilot
Returns direction of desired robot facing
getHeading() - Method in class lejos.robotics.navigation.Pose
returns the heading (direction angle) of the Pose
getHeading() - Method in class lejos.robotics.navigation.Waypoint
 
getHeading(float, float) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Given the former heading and the change in heading, this method will calculate a new heading.
getHeading(Point, Point) - Static method in class lejos.robotics.navigation.ArcAlgorithms
Calculates the heading designated by two points.
getHeadingError() - Method in class lejos.robotics.navigation.CompassPilot
Determines the difference between actual compass direction and desired heading in degrees
getHeight() - Method in class lejos.robotics.mapping.OccupancyGridMap
 
getIterationCount() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
getIterationCount() - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
getIterations() - Method in class lejos.robotics.localization.MCLParticleSet
 
getLargestIndex(ArrayList<Double>) - Static method in class lejos.robotics.localization.BeaconPoseProvider
 
getLeftCount() - Method in class lejos.robotics.navigation.DifferentialPilot
Returns the tachoCount of the left motor
getLinearAcceleration() - Method in class lejos.robotics.navigation.DifferentialPilot
 
getLinearAcceleration() - Method in interface lejos.robotics.navigation.MoveController
Returns the acceleration at which the robot accelerates at the start of a move and decelerates at the end of a move.
getLinearSpeed() - Method in class lejos.robotics.navigation.DifferentialPilot
 
getLinearSpeed() - Method in interface lejos.robotics.navigation.MoveController
Returns the speed at which the robot will travel forward and backward (and to some extent arcs, although actual arc speed is slightly less).
getLines() - Method in class lejos.robotics.mapping.LineMap
Get the lines as an array
getLocation() - Method in class lejos.robotics.navigation.Pose
Get the location as a Point
getLocation() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
return the location of this node
getLocation() - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
return the location of this node
getLowestCost(Collection<Node>) - Static method in class lejos.robotics.pathfinding.AstarSearchAlgorithm
Finds the node within a set of neighbors with the least cost (potentially shortest distance to goal).
getMap() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
getMap() - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
getMaxAngularSpeed() - Method in class lejos.robotics.navigation.DifferentialPilot
 
getMaxAngularSpeed() - Method in interface lejos.robotics.navigation.RotateMoveController
returns the maximum value of the rotation speed;
getMaxDistance() - Method in class lejos.robotics.objectdetection.RangeFeatureDetector
Returns the maximum distance the FeatureDetector will return for detected objects.
getMaxHeadingError() - Method in class lejos.robotics.navigation.Waypoint
 
getMaxLinearSpeed() - Method in class lejos.robotics.navigation.DifferentialPilot
 
getMaxLinearSpeed() - Method in interface lejos.robotics.navigation.MoveController
Returns the maximum speed at which this robot is capable of traveling forward and backward.
getMaxPositionError() - Method in class lejos.robotics.navigation.Waypoint
 
getMaxRotateSpeed() - Method in class lejos.robotics.navigation.DifferentialPilot
 
getMaxWeight() - Method in class lejos.robotics.localization.MCLParticleSet
The highest weight of any particle
getMaxX() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the maximum value of X in the particle set
getMaxY() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the maximum value of Y in the particle set;
getMesh() - Method in class lejos.robotics.pathfinding.FourWayGridMesh
 
getMesh() - Method in interface lejos.robotics.pathfinding.NavigationMesh
Returns a collection of all nodes within this navigation mesh.
getMinRadius() - Method in interface lejos.robotics.navigation.ArcMoveController
The minimum steering radius this vehicle is capable of when traveling in an arc.
getMinRadius() - Method in class lejos.robotics.navigation.DifferentialPilot
 
getMinX() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the minimum value of X in the particle set;
getMinY() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the minimum value of Y in the particle set;
getMoveController() - Method in class lejos.robotics.navigation.Navigator
Returns the MoveController belonging to this object.
getMovement() - Method in class lejos.robotics.navigation.DifferentialPilot
 
getMovement() - Method in interface lejos.robotics.navigation.MoveProvider
Returns the move made since the move started, but before it has completed.
getMovementIncrement() - Method in class lejos.robotics.navigation.DifferentialPilot
 
getMoveType() - Method in class lejos.robotics.navigation.Move
Get the type of the movement performed
getNeighbors() - Method in class lejos.robotics.pathfinding.Node
Returns all the neighbors which this node is connected to.
getNeighbors() - Method in class lejos.robotics.pathfinding.RandomSelfGeneratingNode
When this method is called the first time, it randomly generates a set of neighbors according to the parameters in the constructor.
getNodeCount() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
getNodeCount() - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
getOccupied(int, int) - Method in class lejos.robotics.mapping.OccupancyGridMap
 
getOccupiedThreshold() - Method in class lejos.robotics.mapping.OccupancyGridMap
 
getParticle(int) - Method in class lejos.robotics.localization.MCLParticleSet
Get a specific particle
getParticles() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the particle set
getPath() - Method in class lejos.robotics.navigation.Navigator
Gets the current path
getPose() - Method in class lejos.robotics.localization.BeaconPoseProvider
 
getPose() - Method in class lejos.robotics.localization.CompassPoseProvider
 
getPose() - Method in class lejos.robotics.localization.MCLParticle
Return the pose of this particle
getPose() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the best best estimate of the current pose;
getPose() - Method in class lejos.robotics.localization.OdometryPoseProvider
returns a new pose that represents the current location and heading of the robot.
getPose() - Method in interface lejos.robotics.localization.PoseProvider
 
getPose() - Method in class lejos.robotics.navigation.Waypoint
Return a Pose that represents the way point.
getPose() - Method in class lejos.robotics.objectdetection.RangeFeature
 
getPoseProvider() - Method in class lejos.robotics.navigation.Navigator
Returns the PoseProvider
getPredecessor() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
get the predecessor of this node in the shortest path from the start
getPredecessor() - Method in class lejos.robotics.pathfinding.Node
Used by A* search.
getPredecessor() - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
get the predecessor of this node in the shortest path from the start
getRangeReading() - Method in interface lejos.robotics.objectdetection.Feature
Returns the RangeReading for this particular detected feature.
getRangeReading() - Method in class lejos.robotics.objectdetection.RangeFeature
 
getRangeReadings() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns most recent range readings
getRangeReadings() - Method in interface lejos.robotics.objectdetection.Feature
Returns a set of RangeReadings for a number of detected objects.
getRangeReadings() - Method in class lejos.robotics.objectdetection.RangeFeature
 
getReading(int, RangeReadings, RangeMap) - Method in class lejos.robotics.localization.MCLParticle
Get a specific reading
getReadings() - Method in class lejos.robotics.localization.MCLPoseProvider
Get the current range readings
getReadings(RangeReadings, RangeMap) - Method in class lejos.robotics.localization.MCLParticle
 
getResolution() - Method in class lejos.robotics.mapping.OccupancyGridMap
 
getRightCount() - Method in class lejos.robotics.navigation.DifferentialPilot
Returns the tachoCount of the right motor
getRotateSpeed() - Method in class lejos.robotics.navigation.Move
Get the rotate speed
getRoute(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
helper method for find path()
calculates the route backtracking through predecessor chain
getRoute(ShortestPathFinder.Node) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
helper method for find path()
calculates the route backtracking through predecessor chain
getScanner() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the range scanner
getSigmaHeading() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the standard deviation of the heading values in the particle set;
getSigmaX() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the standard deviation of the X values in the particle set;
getSigmaY() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the standard deviation of the Y values in the particle set;
getSourceDistance() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
return the shortest path length to this node from the start node
getSourceDistance() - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
Return the shortest path length to this node from the start node
getTimeStamp() - Method in class lejos.robotics.navigation.Move
The time stamp is the system clock at the time the Move object is created.
getTimeStamp() - Method in interface lejos.robotics.objectdetection.Feature
The time-stamp is the recorded system time when the range reading was taken.
getTimeStamp() - Method in class lejos.robotics.objectdetection.RangeFeature
 
getTravelSpeed() - Method in class lejos.robotics.navigation.Move
Get the travel speed
getTriangleAngle(Point, Point, Point) - Static method in class lejos.robotics.navigation.ArcAlgorithms
This method calculates the angle generated by three points.
getTurnRate() - Method in class lejos.robotics.navigation.DifferentialPilot
Get the turn rate for arc and steer commands
getWaypoint() - Method in class lejos.robotics.navigation.Navigator
Returns the waypoint to which the robot is presently moving.
getWeight() - Method in class lejos.robotics.localization.MCLParticle
Return the weight of this particle
getWidth() - Method in class lejos.robotics.mapping.OccupancyGridMap
 
getX() - Method in class lejos.robotics.navigation.Pose
Get the X coordinate
getX() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
get the X coordinate of this node
getX() - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
get the X coordinate of this node
getXRange() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns the difference between max X and min X
getY() - Method in class lejos.robotics.navigation.Pose
Get the Y coordinate
getY() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
get the Y coordinate of thes Node
getY() - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
get the Y coordinate of the Node
getYRange() - Method in class lejos.robotics.localization.MCLPoseProvider
Return difference between max Y and min Y
goal - Static variable in class lejos.robotics.pathfinding.RandomSelfGeneratingNode
 
goTo(float, float) - Method in class lejos.robotics.navigation.Navigator
Starts the moving toward the destination Waypoint created from the parameters.
goTo(float, float, float) - Method in class lejos.robotics.navigation.Navigator
Starts the moving toward the destination Waypoint created from the parameters.
goTo(Waypoint) - Method in class lejos.robotics.navigation.Navigator
Starts the robot moving toward the destination.
grid_space - Static variable in class lejos.robotics.pathfinding.GridNode
 
GridNode - Class in lejos.robotics.pathfinding
 
GridNode(float, float, float) - Constructor for class lejos.robotics.pathfinding.GridNode
 
gridspace - Variable in class lejos.robotics.pathfinding.FourWayGridMesh
 

H

h_score - Variable in class lejos.robotics.pathfinding.Node
 
hasScanned - Variable in class lejos.robotics.localization.BeaconPoseProvider
 
heading - Variable in class lejos.robotics.localization.OdometryPoseProvider
 
heading - Variable in class lejos.robotics.navigation.Waypoint
 
headingRequired - Variable in class lejos.robotics.navigation.Waypoint
 
height - Variable in class lejos.robotics.mapping.OccupancyGridMap
 

I

in - Variable in class lejos.robotics.mapping.SVGMapLoader
 
inCandidateSet(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
helper method for findPath; check if aNode is in the set of candidate nodes
inCandidateSet(ShortestPathFinder.Node) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
helper method for findPath; check if aNode is in the set of candidate nodes
incomplete - Variable in class lejos.robotics.localization.MCLPoseProvider
 
incompleteRanges() - Method in class lejos.robotics.localization.MCLPoseProvider
returns range scanner failure status
initialize() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
initialize() - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
inReachedSet(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
helper method for findPath; check if aNode is in the set of reached nodes
inReachedSet(ShortestPathFinder.Node) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
helper method for findPath; check if aNode is in the set of reached nodes
inside(Point) - Method in class lejos.robotics.mapping.LineMap
Check if a point is within the mapped area
inside(Point) - Method in interface lejos.robotics.mapping.RangeMap
Test if a point is within the mapped area
isBlocked(ShortestPathFinder.Node) - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
isBusy() - Method in class lejos.robotics.localization.MCLPoseProvider
returns true if particle weights are being updated.
isEnabled() - Method in interface lejos.robotics.objectdetection.FeatureDetector
Indicates if automatic scanning mode and listener notification is currently enabled.
isEnabled() - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
isEnabled() - Method in class lejos.robotics.objectdetection.FusorDetector
 
isFree(int, int) - Method in class lejos.robotics.mapping.OccupancyGridMap
 
isHeadingRequired() - Method in class lejos.robotics.navigation.Waypoint
 
isLost() - Method in class lejos.robotics.localization.MCLPoseProvider
returns lost status - all particles have very low probability weights
isMoving - Variable in class lejos.robotics.navigation.Move
 
isMoving() - Method in class lejos.robotics.navigation.DifferentialPilot
 
isMoving() - Method in class lejos.robotics.navigation.Move
Test if move was in progress
isMoving() - Method in interface lejos.robotics.navigation.MoveController
true if the robot is moving
isMoving() - Method in class lejos.robotics.navigation.Navigator
Returns true if the robot is moving toward a waypoint.
isOccupied(int, int) - Method in class lejos.robotics.mapping.OccupancyGridMap
 
isStalled() - Method in class lejos.robotics.navigation.DifferentialPilot
 
isTraveling() - Method in class lejos.robotics.navigation.CompassPilot
returns returns true if the robot is travelling for a specific distance;
isUpdated() - Method in class lejos.robotics.localization.MCLPoseProvider
Returns update success flag

K

keepGoing - Variable in class lejos.robotics.localization.MCLPoseProvider.Updater
 

L

lejos.robotics.localization - package lejos.robotics.localization
Localization support
lejos.robotics.mapping - package lejos.robotics.mapping
Support for maps
lejos.robotics.navigation - package lejos.robotics.navigation
Navigation classes.
lejos.robotics.objectdetection - package lejos.robotics.objectdetection
Object detection classes.
lejos.robotics.pathfinding - package lejos.robotics.pathfinding
Path finding classes.
lengthenLines(float) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
lengthens all the lines in the map by delta at each end
lengthenLines(float) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
lengthens all the lines in the map by delta at each end
LineFollowingMoveController - Interface in lejos.robotics.navigation
 
LineMap - Class in lejos.robotics.mapping
A map of a room or other closed environment, represented by line segments
LineMap() - Constructor for class lejos.robotics.mapping.LineMap
Constructor to use when map will be loaded from a data stream
LineMap(Line[], Rectangle) - Constructor for class lejos.robotics.mapping.LineMap
Create a map from an array of line segments and a bounding rectangle
lines - Variable in class lejos.robotics.mapping.LineMap
 
listeners - Variable in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
listeners - Variable in class lejos.robotics.objectdetection.FusorDetector
 
listeners - Variable in class lejos.robotics.objectdetection.TouchFeatureDetector
 
listeners - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder
 
listeners - Variable in class lejos.robotics.pathfinding.NodePathFinder
 
listeners - Variable in class lejos.robotics.pathfinding.RandomPathFinder
 
listeners - Variable in class lejos.robotics.pathfinding.ShortestPathFinder
 
loadObject(DataInputStream) - Method in class lejos.robotics.localization.MCLParticleSet
Load serialized particles from a data input stream
loadObject(DataInputStream) - Method in class lejos.robotics.localization.MCLPoseProvider
Load serialized estimated pose from a data input stream
loadObject(DataInputStream) - Method in class lejos.robotics.mapping.LineMap
Load a map from a DataInputStream
loadObject(DataInputStream) - Method in class lejos.robotics.navigation.Move
 
loadObject(DataInputStream) - Method in class lejos.robotics.navigation.Pose
 
loadObject(DataInputStream) - Method in class lejos.robotics.navigation.Waypoint
 
loadObject(DataInputStream) - Method in class lejos.robotics.objectdetection.RangeFeature
 
loadObject(DataInputStream) - Method in class lejos.robotics.pathfinding.Path
 
locate() - Method in interface lejos.robotics.localization.BeaconLocator
This method performs a scan around the robot.
lost - Variable in class lejos.robotics.localization.MCLPoseProvider
 

M

main_loop - Variable in class lejos.robotics.pathfinding.AstarSearchAlgorithm
 
map - Variable in class lejos.robotics.localization.MCLParticleSet
 
map - Variable in class lejos.robotics.localization.MCLPoseProvider
 
map - Variable in class lejos.robotics.pathfinding.FourWayGridMesh
 
map - Variable in class lejos.robotics.pathfinding.RandomPathFinder
 
MAX_BOUND - Static variable in class lejos.robotics.mapping.SVGMapLoader
 
max_dist - Variable in class lejos.robotics.objectdetection.RangeFeatureDetector
 
maxDist - Variable in class lejos.robotics.pathfinding.RandomSelfGeneratingNode
 
maxDistance - Variable in class lejos.robotics.pathfinding.RandomPathFinder
 
maxHeadingError - Variable in class lejos.robotics.navigation.Waypoint
 
maxIterations - Static variable in class lejos.robotics.localization.MCLParticleSet
 
maxIterations - Variable in class lejos.robotics.pathfinding.RandomPathFinder
 
maxPositionError - Variable in class lejos.robotics.navigation.Waypoint
 
maxRange - Variable in class lejos.robotics.pathfinding.RandomPathFinder
 
maxWeight - Variable in class lejos.robotics.localization.MCLParticleSet
 
maxX - Variable in class lejos.robotics.localization.MCLPoseProvider
 
maxY - Variable in class lejos.robotics.localization.MCLPoseProvider
 
MCLParticle - Class in lejos.robotics.localization
Represents a particle for the particle filtering algorithm.
MCLParticle(Pose) - Constructor for class lejos.robotics.localization.MCLParticle
Create a particle with a specific pose
MCLParticleSet - Class in lejos.robotics.localization
Represents a particle set for the particle filtering algorithm.
MCLParticleSet(RangeMap, int, int) - Constructor for class lejos.robotics.localization.MCLParticleSet
Create a set of particles randomly distributed within the given map.
MCLParticleSet(RangeMap, int, int, RangeReadings, float, float) - Constructor for class lejos.robotics.localization.MCLParticleSet
Generates a set of particles within the map that have a minimum weight as as calculated from the particle pose, the range readings and the map.
MCLParticleSet(RangeMap, int, Pose, float, float) - Constructor for class lejos.robotics.localization.MCLParticleSet
Generates a circular cloud of particles centered on initialPose with random normal radius and angle, and random normal heading.
MCLPoseProvider - Class in lejos.robotics.localization
Maintains an estimate of the robot pose using sensor data.
MCLPoseProvider(RangeMap, int, int) - Constructor for class lejos.robotics.localization.MCLPoseProvider
Constructor for use on PC
MCLPoseProvider(MoveProvider, RangeScanner, RangeMap, int, int) - Constructor for class lejos.robotics.localization.MCLPoseProvider
Allocates a new MCLPoseProvider.
MCLPoseProvider.Updater - Class in lejos.robotics.localization
Predicts particle pose from odometry data.
mesh - Variable in class lejos.robotics.pathfinding.FourWayGridMesh
 
mesh - Variable in class lejos.robotics.pathfinding.NodePathFinder
 
minGain - Variable in class lejos.robotics.pathfinding.RandomPathFinder
 
minX - Variable in class lejos.robotics.localization.MCLPoseProvider
 
minY - Variable in class lejos.robotics.localization.MCLPoseProvider
 
Monitor() - Constructor for class lejos.robotics.navigation.DifferentialPilot.Monitor
 
MonitorThread() - Constructor for class lejos.robotics.objectdetection.FeatureDetectorAdapter.MonitorThread
 
more - Variable in class lejos.robotics.navigation.DifferentialPilot.Monitor
 
more - Variable in class lejos.robotics.navigation.Navigator.Nav
 
Move - Class in lejos.robotics.navigation
Models a movement performed by a pilot
Move(boolean, float, float) - Constructor for class lejos.robotics.navigation.Move
Alternate constructor that uses angle and turn radius instead.
Move(float, float, boolean) - Constructor for class lejos.robotics.navigation.Move
Create a movement object to record a movement made by a pilot.
Move(Move.MoveType, float, float, boolean) - Constructor for class lejos.robotics.navigation.Move
Create a movement object to record a movement made by a pilot.
Move(Move.MoveType, float, float, float, float, boolean) - Constructor for class lejos.robotics.navigation.Move
Create a movement object to record a movement made by a pilot.
Move.MoveType - Enum in lejos.robotics.navigation
The type of movement made in sufficient detail to allow errors in the movement to be modeled.
MoveController - Interface in lejos.robotics.navigation
 
MoveListener - Interface in lejos.robotics.navigation
Any class that wants to be updated automatically by a MoveProvider should implement this interface.
movementActive() - Method in class lejos.robotics.navigation.DifferentialPilot
Called to indicate that the motors are now running and should be monitored for movement.
movementStart() - Method in class lejos.robotics.navigation.DifferentialPilot
called at start of a movement to inform the listeners that a movement has started.
movementStop() - Method in class lejos.robotics.navigation.DifferentialPilot
called by Arc() ,travel(),rotate(),stop() rotationStopped() calls moveStopped on listener
MoveProvider - Interface in lejos.robotics.navigation
Should be implemented by a Pilot that provides a partial movement to a pose when requested.
moves - Variable in class lejos.robotics.localization.BeaconPoseProvider
 
moveStarted(Move, MoveProvider) - Method in class lejos.robotics.localization.BeaconPoseProvider
 
moveStarted(Move, MoveProvider) - Method in class lejos.robotics.localization.MCLPoseProvider
Required by MoveListener interface; does nothing
moveStarted(Move, MoveProvider) - Method in class lejos.robotics.localization.OdometryPoseProvider
called by a MoveProvider when movement starts
moveStarted(Move, MoveProvider) - Method in interface lejos.robotics.navigation.MoveListener
Called when a Move Provider starts a move
moveStopped(Move) - Method in class lejos.robotics.localization.MCLPoseProvider.Updater
 
moveStopped(Move, MoveProvider) - Method in class lejos.robotics.localization.BeaconPoseProvider
 
moveStopped(Move, MoveProvider) - Method in class lejos.robotics.localization.MCLPoseProvider
Required by MoveListener interface.
moveStopped(Move, MoveProvider) - Method in class lejos.robotics.localization.OdometryPoseProvider
called by a MoveProvider when movement ends
moveStopped(Move, MoveProvider) - Method in interface lejos.robotics.navigation.MoveListener
Called by the movement provider when a move stops
moveType - Variable in class lejos.robotics.navigation.Move
 
MoveType() - Constructor for enum lejos.robotics.navigation.Move.MoveType
 
moveUpdate(float) - Method in class lejos.robotics.navigation.Pose
Move the specified distance in the direction of current heading.
mp - Variable in class lejos.robotics.localization.OdometryPoseProvider
 
MULTIPLIER - Static variable in class lejos.robotics.pathfinding.Node
This constant is multiplied with the float coordinate to get an integer for faster internal computations.
MULTIPOINT - Static variable in class lejos.robotics.mapping.ShapefileLoader
 

N

Nav() - Constructor for class lejos.robotics.navigation.Navigator.Nav
 
NavigationListener - Interface in lejos.robotics.navigation
Interface for informing listeners that a way point has been reached.
NavigationMesh - Interface in lejos.robotics.pathfinding
A navigation mesh is a set of nodes covering a map area which represent branching pathways for the vehicle to move from one location to another.
Navigator - Class in lejos.robotics.navigation
This class controls a robot to traverse a Path, a sequence of Waypoints.
Navigator(MoveController) - Constructor for class lejos.robotics.navigation.Navigator
Allocates a Navigator object, using pilot that implements the ArcMoveController interface.
Navigator(MoveController, PoseProvider) - Constructor for class lejos.robotics.navigation.Navigator
Allocates a Navigator object using a pilot and a custom poseProvider, rather than the default OdometryPoseProvider.
Navigator.Nav - Class in lejos.robotics.navigation
This inner class runs the thread that processes the waypoint queue
neighbor_loop - Variable in class lejos.robotics.pathfinding.AstarSearchAlgorithm
 
neighbors - Variable in class lejos.robotics.pathfinding.Node
List of neighbors to this node.
neighbors() - Method in class lejos.robotics.pathfinding.Node
Indicates the number of neighbors (nodes connected to this node).
Node - Class in lejos.robotics.pathfinding
This class represents a Node which can be connected to other neighboring nodes.
Node(float, float) - Constructor for class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
Node(float, float) - Constructor for class lejos.robotics.pathfinding.Node
Creates a new instance of a node.
Node(float, float) - Constructor for class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
Node(Point) - Constructor for class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
Node(Point) - Constructor for class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
NodePathFinder - Class in lejos.robotics.pathfinding
This path finder class uses one of the common search algorithms (e.g.
NodePathFinder(SearchAlgorithm) - Constructor for class lejos.robotics.pathfinding.NodePathFinder
Instantiates a NodePathFinder object using a specified algorithm.
NodePathFinder(SearchAlgorithm, NavigationMesh) - Constructor for class lejos.robotics.pathfinding.NodePathFinder
Instantiates a NodePathFinder object using a specified algorithm.
normalize(float) - Method in class lejos.robotics.localization.OdometryPoseProvider
 
normalize(float) - Method in class lejos.robotics.navigation.CompassPilot
 
notifyListeners(Feature) - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
notifyListeners(Feature) - Method in class lejos.robotics.objectdetection.FusorDetector
 
notifyListeners(Feature) - Method in class lejos.robotics.objectdetection.TouchFeatureDetector
 
NotifyThread() - Constructor for class lejos.robotics.objectdetection.FusorDetector.NotifyThread
 
NULL_SHAPE - Static variable in class lejos.robotics.mapping.ShapefileLoader
 
numParticles - Variable in class lejos.robotics.localization.MCLParticleSet
 
numParticles - Variable in class lejos.robotics.localization.MCLPoseProvider
 
numParticles() - Method in class lejos.robotics.localization.MCLParticleSet
Return the number of particles in the set

O

OccupancyGridMap - Class in lejos.robotics.mapping
 
OccupancyGridMap(int, int, double, double, double) - Constructor for class lejos.robotics.mapping.OccupancyGridMap
 
occupiedThreshold - Variable in class lejos.robotics.mapping.OccupancyGridMap
 
OdometryPoseProvider - Class in lejos.robotics.localization
A PoseProvider keeps track of the robot Pose.
OdometryPoseProvider(MoveProvider) - Constructor for class lejos.robotics.localization.OdometryPoseProvider
Allocates a new OdometryPoseProivder and registers it with the MovePovider as a listener.
opp - Variable in class lejos.robotics.localization.BeaconPoseProvider
 

P

particles - Variable in class lejos.robotics.localization.MCLParticleSet
 
particles - Variable in class lejos.robotics.localization.MCLPoseProvider
 
Path - Class in lejos.robotics.pathfinding
Represents a path consisting of an ordered collection of waypoints
Path() - Constructor for class lejos.robotics.pathfinding.Path
 
pathComplete(Waypoint, Pose, int) - Method in interface lejos.robotics.navigation.NavigationListener
Called when the robot has reached the last Waypoint of the path
pathCompleted() - Method in class lejos.robotics.navigation.Navigator
Returns true if the the final waypoint has been reached
PathFinder - Interface in lejos.robotics.pathfinding
This class creates a set of waypoints connected by straight lines that lead from one location to another without colliding with mapped geometry.
pathGenerated() - Method in class lejos.robotics.navigation.Navigator
 
pathGenerated() - Method in interface lejos.robotics.navigation.WaypointListener
Called when generation of the path is complete
pathInterrupted(Waypoint, Pose, int) - Method in interface lejos.robotics.navigation.NavigationListener
called when the robot has stopped, not at a Waypoint
POINT - Static variable in class lejos.robotics.mapping.ShapefileLoader
 
pointAt(float, float) - Method in class lejos.robotics.navigation.Pose
Returns the point at distance from the location of this pose, in the direction bearing relative to the X axis.
POLYGON - Static variable in class lejos.robotics.mapping.ShapefileLoader
 
POLYLINE - Static variable in class lejos.robotics.mapping.ShapefileLoader
 
pose - Variable in class lejos.robotics.localization.MCLParticle
 
pose - Variable in class lejos.robotics.objectdetection.RangeFeature
 
Pose - Class in lejos.robotics.navigation
Represents the location and heading(direction angle) of a robot.
This class includes methods for updating the Pose to in response to basic robot movements.
Pose() - Constructor for class lejos.robotics.navigation.Pose
allocate a new Pose at the origin, heading = 0:the direction the positive X axis
Pose(float, float, float) - Constructor for class lejos.robotics.navigation.Pose
Allocate a new pose at location (x,y) with specified heading in degrees.
poseProvider - Variable in class lejos.robotics.navigation.Navigator
 
PoseProvider - Interface in lejos.robotics.localization
Provides the coordinate and heading info via a Pose object.
pp - Variable in class lejos.robotics.objectdetection.RangeFeatureDetector
 
prev_time - Variable in class lejos.robotics.objectdetection.FeatureDetectorAdapter.MonitorThread
 

Q

quickStop() - Method in class lejos.robotics.navigation.DifferentialPilot
Stops the robot almost immediately.

R

radius(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Returns the radius of the turn made by steer(turnRate) Used in for planned distance at start of arc and steer moves.
rand - Static variable in class lejos.robotics.localization.MCLParticle
 
random - Variable in class lejos.robotics.localization.MCLParticleSet
 
RandomPathFinder - Class in lejos.robotics.pathfinding
PathFinder that takes a map and a dummy set of range readings.
RandomPathFinder(RangeMap, RangeReadings) - Constructor for class lejos.robotics.pathfinding.RandomPathFinder
 
RandomSelfGeneratingNode - Class in lejos.robotics.pathfinding
This Node is able to randomly generate its own neighbors via the getNeighbors() method.
RandomSelfGeneratingNode(float, float, float, int) - Constructor for class lejos.robotics.pathfinding.RandomSelfGeneratingNode
Creates a node that will randomly generate 'connections' number of neighbors when getNeighbors() is called.
RandomSelfGeneratingNode(float, float, float, int, Node) - Constructor for class lejos.robotics.pathfinding.RandomSelfGeneratingNode
Creates a node that will randomly generate 'connections' number of neighbors when getNeighbors() is called.
range - Variable in class lejos.robotics.objectdetection.TouchFeatureDetector
 
range(Pose) - Method in class lejos.robotics.mapping.LineMap
Calculate the range of a robot to the nearest wall
range(Pose) - Method in interface lejos.robotics.mapping.RangeMap
The the range to the nearest wall (or other feature)
range_finder - Variable in class lejos.robotics.objectdetection.RangeFeatureDetector
 
RangeFeature - Class in lejos.robotics.objectdetection
This class is a basic data container for information retrieved about an object detected by sensors.
RangeFeature(RangeReading) - Constructor for class lejos.robotics.objectdetection.RangeFeature
Creates a RangeFeature containing a single RangeReading.
RangeFeature(RangeReadings) - Constructor for class lejos.robotics.objectdetection.RangeFeature
Creates a RangeFeature containing multiple RangeReadings.
RangeFeature(RangeReadings, Pose) - Constructor for class lejos.robotics.objectdetection.RangeFeature
Creates a RangeFeature containing multiple RangeReadings.
RangeFeatureDetector - Class in lejos.robotics.objectdetection
The RangeFeatureDetector used a RangeFinder to locate objects (known as features when mapping).
RangeFeatureDetector(RangeFinder, float, int) - Constructor for class lejos.robotics.objectdetection.RangeFeatureDetector
This constructor allows you to specify the sensor, the maximum distance to report a detection, and the delay between scanning the sensor.
RangeFeatureDetector(RangeFinder, float, int, double) - Constructor for class lejos.robotics.objectdetection.RangeFeatureDetector
This constructor allows you to specify the sensor, the maximum distance to report a detection, the delay between scanning the sensor, and the angle the sensor is pointed.
RangeMap - Interface in lejos.robotics.mapping
The RangeMap interface supports determining the range to a feature on the map (such as a wall), from an object with a specific pose.
readings - Variable in class lejos.robotics.localization.MCLPoseProvider
 
readings - Variable in class lejos.robotics.objectdetection.FusorDetector
 
readings - Variable in class lejos.robotics.pathfinding.RandomPathFinder
 
readLEDouble() - Method in class lejos.robotics.mapping.ShapefileLoader
Reads a little endian double into a big endian double
readLEInt() - Method in class lejos.robotics.mapping.ShapefileLoader
Translates a little endian int into a big endian int
readLELong() - Method in class lejos.robotics.mapping.ShapefileLoader
Translates a little endian long into a big endian long
readLineMap() - Method in class lejos.robotics.mapping.ShapefileLoader
Retrieves a LineMap object from the Shapefile input stream.
readLineMap() - Method in class lejos.robotics.mapping.SVGMapLoader
 
reconstructPath(Node, Node, Collection<Waypoint>) - Static method in class lejos.robotics.pathfinding.AstarSearchAlgorithm
Given the current node and the start node, this method retraces the completed path.
regenerate() - Method in class lejos.robotics.pathfinding.FourWayGridMesh
 
regenerate() - Method in interface lejos.robotics.pathfinding.NavigationMesh
Throws away the previous set of nodes and recalculates them all.
regulator - Variable in class lejos.robotics.navigation.CompassPilot
 
Regulator() - Constructor for class lejos.robotics.navigation.CompassPilot.Regulator
 
relativeBearing(Point) - Method in class lejos.robotics.navigation.Pose
Returns the angle to destination relative to the pose heading;
removeNeighbor(Node) - Method in class lejos.robotics.pathfinding.Node
Removes a node from this node as neighbors, effectively disconnecting them.
removeNode(Node) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
 
removeNode(Node) - Method in interface lejos.robotics.pathfinding.NavigationMesh
Removes a node from the set and removes any existing connections with its neighbors.
resample() - Method in class lejos.robotics.localization.MCLParticleSet
Resample the set picking those with higher weights.
reset() - Method in class lejos.robotics.navigation.CompassPilot
 
reset() - Method in class lejos.robotics.navigation.DifferentialPilot
Resets tacho count for both motors.
resetCartesianZero() - Method in class lejos.robotics.navigation.CompassPilot
 
resolution - Variable in class lejos.robotics.mapping.OccupancyGridMap
 
rotate(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Rotates the NXT robot through a specific angle.
rotate(double) - Method in interface lejos.robotics.navigation.RotateMoveController
Rotates the NXT robot the specified number of degrees; direction determined by the sign of the parameter.
rotate(double, boolean) - Method in class lejos.robotics.navigation.DifferentialPilot
Rotates the NXT robot through a specific angle.
rotate(double, boolean) - Method in interface lejos.robotics.navigation.RotateMoveController
Rotates the NXT robot the specified number of degrees; direction determined by the sign of the parameter.
rotate(float) - Method in class lejos.robotics.navigation.CompassPilot
Rotates the NXT robot through a specific angle; Rotates left if angle is positive, right if negative, Returns when angle is reached.
rotate(float, boolean) - Method in class lejos.robotics.navigation.CompassPilot
robot rotates to the specified compass heading;
rotateLeft() - Method in class lejos.robotics.navigation.DifferentialPilot
 
rotateLeft() - Method in interface lejos.robotics.navigation.RotateMoveController
 
RotateMoveController - Interface in lejos.robotics.navigation
 
rotateRight() - Method in class lejos.robotics.navigation.DifferentialPilot
 
rotateRight() - Method in interface lejos.robotics.navigation.RotateMoveController
 
rotateSpeed - Variable in class lejos.robotics.navigation.Move
 
rotateTo(double) - Method in class lejos.robotics.navigation.Navigator
Rotates the robot to a new absolute heading.
rotateUpdate(float) - Method in class lejos.robotics.navigation.Pose
Rotate the heading through the specified angle
rr - Variable in class lejos.robotics.objectdetection.RangeFeature
 
rrs - Variable in class lejos.robotics.objectdetection.RangeFeature
 
run() - Method in class lejos.robotics.localization.MCLPoseProvider.Updater
 
run() - Method in class lejos.robotics.navigation.CompassPilot.Regulator
 
run() - Method in class lejos.robotics.navigation.DifferentialPilot.Monitor
 
run() - Method in class lejos.robotics.navigation.Navigator.Nav
 
run() - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter.MonitorThread
 
run() - Method in class lejos.robotics.objectdetection.FusorDetector.NotifyThread
 

S

sampleSize() - Method in class lejos.robotics.localization.OdometryPoseProvider
 
scan() - Method in interface lejos.robotics.objectdetection.FeatureDetector
Performs a single scan for an object and returns the results.
scan() - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
scan() - Method in class lejos.robotics.objectdetection.FusorDetector
This method scans all the sensors added to this object and returns the amalgamated results.
scan() - Method in class lejos.robotics.objectdetection.RangeFeatureDetector
 
scan() - Method in class lejos.robotics.objectdetection.TouchFeatureDetector
 
scanInterval - Variable in class lejos.robotics.localization.BeaconPoseProvider
 
scanner - Variable in class lejos.robotics.localization.MCLPoseProvider
 
SearchAlgorithm - Interface in lejos.robotics.pathfinding
An interface for defining generic node search algorithms.
segmentBlocked(DijkstraPathFinder.Node, DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
helper method for findPath().
segmentBlocked(ShortestPathFinder.Node, ShortestPathFinder.Node) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
Helper method for findPath().
serialVersionUID - Static variable in class lejos.robotics.pathfinding.RandomPathFinder
 
setAngleNoiseFactor(float) - Method in class lejos.robotics.localization.MCLParticleSet
Set the distance angle factor
setAngularAcceleration(double) - Method in class lejos.robotics.navigation.DifferentialPilot
 
setAngularAcceleration(double) - Method in interface lejos.robotics.navigation.RotateMoveController
Sets the acceleration at which the robot will accelerate at the start of a move and decelerate at the end of a move.
setAngularSpeed(double) - Method in class lejos.robotics.navigation.DifferentialPilot
sets the rotation speed of the vehicle, degrees per second
setAngularSpeed(double) - Method in interface lejos.robotics.navigation.RotateMoveController
sets the rotation speed of the robot (the angular velocity of the rotate() methods)
setBorder(int) - Method in class lejos.robotics.localization.MCLParticleSet
Set border where no particles should be generated
setClearance(float) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
Changes the safety zone between all nodes/connections and map geometry.
setClearance(float) - Method in class lejos.robotics.pathfinding.RandomPathFinder
Set the clearance around the edge of the map.
setDebug(boolean) - Static method in class lejos.robotics.localization.MCLParticle
 
setDebug(boolean) - Static method in class lejos.robotics.localization.MCLParticleSet
Set system out debugging on or off
setDebug(boolean) - Method in class lejos.robotics.localization.MCLPoseProvider
Set debugging on or off
setDebug(boolean) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
setDelay(int) - Method in interface lejos.robotics.objectdetection.FeatureDetector
Sets the minimum delay between readings from the feature detector.
setDelay(int) - Method in class lejos.robotics.objectdetection.FeatureDetectorAdapter
 
setDelay(int) - Method in class lejos.robotics.objectdetection.FusorDetector
 
setDistanceNoiseFactor(float) - Method in class lejos.robotics.localization.MCLParticleSet
Set the distance noise factor
setDynamics(float, float) - Method in class lejos.robotics.navigation.Move
use this method to recycle an existing Move instead of creating a new one
setG_Score(float) - Method in class lejos.robotics.pathfinding.Node
Method used by A* to calculate search score.
setGridSpacing(float) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
Change the size of each grid square.
setH_Score(float) - Method in class lejos.robotics.pathfinding.Node
Method used by A* to calculate search score.
setHeading(float) - Method in class lejos.robotics.localization.OdometryPoseProvider
 
setHeading(float) - Method in class lejos.robotics.navigation.CompassPilot
sets direction of desired robot facing in degrees
setHeading(float) - Method in class lejos.robotics.navigation.Pose
 
setInitialPose(RangeReadings, float) - Method in class lejos.robotics.localization.MCLPoseProvider
Generates an initial particle set using the range readings.
setInitialPose(Pose, float, float) - Method in class lejos.robotics.localization.MCLPoseProvider
Generates an initial particle set in a circular normal distribution, centered on aPose.
setLinearAcceleration(double) - Method in class lejos.robotics.navigation.DifferentialPilot
 
setLinearAcceleration(double) - Method in interface lejos.robotics.navigation.MoveController
Sets the acceleration at which the robot will accelerate at the start of a move and decelerate at the end of a move.
setLinearSpeed(double) - Method in class lejos.robotics.navigation.DifferentialPilot
set travel speed in wheel diameter units per second
setLinearSpeed(double) - Method in interface lejos.robotics.navigation.MoveController
Sets the speed at which the robot will travel forward and backward (and to some extent arcs, although actual arc speed is slightly less).
setLocation(float, float) - Method in class lejos.robotics.navigation.Pose
Sets the location of this pose to a new point at x,y;
setLocation(Point) - Method in class lejos.robotics.navigation.Pose
Set the location of the pose
setMap(ArrayList<Line>) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
setMap(ArrayList<Line>) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
setMap(LineMap) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
setMap(LineMap) - Method in class lejos.robotics.pathfinding.FourWayGridMesh
Feeds this class a new map.
setMap(LineMap) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
setMap(RangeMap) - Method in class lejos.robotics.localization.MCLPoseProvider
Associates a map with the MCLPoseProvider (for example a map send from the PC).
setMaxDistance(float) - Method in class lejos.robotics.objectdetection.RangeFeatureDetector
Sets the maximum distance to register detected objects from the range finder.
setMaxDistance(float) - Method in class lejos.robotics.pathfinding.RandomPathFinder
Set the maximum distance between waypoints
setMaxHeadingError(double) - Method in class lejos.robotics.navigation.Waypoint
 
setMaxIterations(int) - Method in class lejos.robotics.localization.MCLParticleSet
Set the maximum iterations for the resample algorithm
setMaxIterations(int) - Method in class lejos.robotics.pathfinding.RandomPathFinder
Set the maximum number of iterations before giving up when searching for a path
setMaxPositionError(double) - Method in class lejos.robotics.navigation.Waypoint
 
setMaxRange(float) - Method in class lejos.robotics.pathfinding.RandomPathFinder
Set the maximum valid range readings
setMinRadius(double) - Method in interface lejos.robotics.navigation.ArcMoveController
Set the radius of the minimum turning circle.
setMinRadius(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Set the radius of the minimum turning circle.
setMotorAccel(int) - Method in class lejos.robotics.navigation.DifferentialPilot
helper method for setAcceleration and quickStop
setNavMesh(NavigationMesh) - Method in class lejos.robotics.pathfinding.NodePathFinder
Method for changing the navigation mesh after this has been instantiated.
setOccupied(int, int, int) - Method in class lejos.robotics.mapping.OccupancyGridMap
 
setParticles(MCLParticleSet) - Method in class lejos.robotics.localization.MCLPoseProvider
Associate a particle set with the MCLPoseProvider (e.g.
setPath(Path) - Method in class lejos.robotics.navigation.Navigator
Sets the path that the Navigator will traverse.
setPose(Pose) - Method in class lejos.robotics.localization.BeaconPoseProvider
 
setPose(Pose) - Method in class lejos.robotics.localization.MCLPoseProvider
set the initial pose cloud with radius noise 1 and heading noise 1
setPose(Pose) - Method in class lejos.robotics.localization.OdometryPoseProvider
 
setPose(Pose) - Method in interface lejos.robotics.localization.PoseProvider
 
setPoseProvider(PoseProvider) - Method in class lejos.robotics.navigation.Navigator
Sets the PoseProvider after construction of the Navigator
setPoseProvider(PoseProvider) - Method in class lejos.robotics.objectdetection.RangeFeatureDetector
 
setPosition(Point) - Method in class lejos.robotics.localization.OdometryPoseProvider
 
setPredecessor(DijkstraPathFinder.Node) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
set the predecessor of this node in the shortest path from the start node
setPredecessor(Node) - Method in class lejos.robotics.pathfinding.Node
Used by A* search.
setPredecessor(ShortestPathFinder.Node) - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
set the predecessor of this node in the shortest path from the start node
setSearchAlgorithm(SearchAlgorithm) - Method in class lejos.robotics.pathfinding.NodePathFinder
Method for changing the search algorithm after this has been instantiated.
setSigma(float) - Method in class lejos.robotics.localization.MCLParticleSet
Set the standard deviation for the sensor probability model
setSourceDistance(float) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
set the distance of this Node from the source
setSourceDistance(float) - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
Set the distance of this Node from the source
setSpeed(int, int) - Method in class lejos.robotics.navigation.DifferentialPilot
 
setValues(Move.MoveType, float, float, boolean) - Method in class lejos.robotics.navigation.Move
use this method to recycle an existing Move instead of creating a new one
setWeight(float) - Method in class lejos.robotics.localization.MCLParticle
Set the weight for this particle
SHAPEFILE_ID - Variable in class lejos.robotics.mapping.ShapefileLoader
 
ShapefileLoader - Class in lejos.robotics.mapping
This class loads map data from a Shapefile and produces a LineMap object, which can be used by the leJOS navigation package.
ShapefileLoader(InputStream) - Constructor for class lejos.robotics.mapping.ShapefileLoader
Creates a ShapefileLoader object using an input stream.
ShortestPathFinder - Class in lejos.robotics.pathfinding
This class calculates the shortest path from a starting point to a finish point.
ShortestPathFinder(LineMap) - Constructor for class lejos.robotics.pathfinding.ShortestPathFinder
 
ShortestPathFinder.Node - Class in lejos.robotics.pathfinding
 
sin(double) - Static method in class lejos.robotics.localization.BeaconTriangle
 
singleStep(boolean) - Method in class lejos.robotics.navigation.Navigator
Controls whether the robot stops at each Waypoint; applies to the current path only.
sortBeacons(ArrayList<Double>, ArrayList<Double>) - Static method in class lejos.robotics.localization.BeaconPoseProvider
This sorts the beacons into the proper order so that beacons.get(0) returns beacon1, and so on.
startPathFinding(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.DijkstraPathFinder
 
startPathFinding(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.NodePathFinder
 
startPathFinding(Pose, Waypoint) - Method in interface lejos.robotics.pathfinding.PathFinder
 
startPathFinding(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.RandomPathFinder
 
startPathFinding(Pose, Waypoint) - Method in class lejos.robotics.pathfinding.ShortestPathFinder
 
steer(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Starts the robot moving forward along a curved path.
steer(double) - Method in interface lejos.robotics.navigation.LineFollowingMoveController
Moves the robot forward while making a curve specified by turnRate.
steer(double, double) - Method in class lejos.robotics.navigation.DifferentialPilot
Moves the robot along a curved path through a specified turn angle.
steer(double, double, boolean) - Method in class lejos.robotics.navigation.DifferentialPilot
Moves the robot along a curved path for a specified angle of rotation.
steerBackward(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Starts the robot moving backward along a curved path.
steerBackward(double) - Method in interface lejos.robotics.navigation.LineFollowingMoveController
Moves the robot backward while making a curve specified by turnRate.
steerPrep(double) - Method in class lejos.robotics.navigation.DifferentialPilot
helper method used by steer(float) and steer(float,float,boolean) sets _outsideSpeed, _insideSpeed, _steerRatio set motor acceleration to help continuous steer and arc moves
stop() - Method in class lejos.robotics.navigation.CompassPilot
Stops the robot soon after the method is executed.
stop() - Method in class lejos.robotics.navigation.DifferentialPilot
Stops the NXT robot.
stop() - Method in interface lejos.robotics.navigation.MoveController
Halts the NXT robot
stop() - Method in class lejos.robotics.navigation.Navigator
Stops the robot.
stopNow() - Method in class lejos.robotics.navigation.CompassPilot
 
STRING_NAME - Static variable in class lejos.robotics.pathfinding.AstarSearchAlgorithm
 
SVGMapLoader - Class in lejos.robotics.mapping
This class loads map data from an SVG and produces a LineMap object, which can be used by the leJOS navigation package.
SVGMapLoader(InputStream) - Constructor for class lejos.robotics.mapping.SVGMapLoader
 

T

timeStamp - Variable in class lejos.robotics.navigation.Move
 
timeStamp - Variable in class lejos.robotics.objectdetection.RangeFeature
 
toString() - Method in class lejos.robotics.navigation.Move
 
toString() - Method in class lejos.robotics.navigation.Pose
return string contains x,y and heading
toString() - Method in class lejos.robotics.pathfinding.AstarSearchAlgorithm
 
toString() - Method in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
toString() - Method in class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
totalWeight - Variable in class lejos.robotics.localization.MCLParticleSet
 
touch_sensor - Variable in class lejos.robotics.objectdetection.TouchFeatureDetector
 
TouchFeatureDetector - Class in lejos.robotics.objectdetection
This class allows a touch sensor to be used as a defacto range sensor by reporting the position of the touch sensor to the object detection API.
TouchFeatureDetector(Touch) - Constructor for class lejos.robotics.objectdetection.TouchFeatureDetector
Creates a touch detector in which the touch sensor is assumed to be situated in the center of the robot.
TouchFeatureDetector(Touch, double, double) - Constructor for class lejos.robotics.objectdetection.TouchFeatureDetector
If you want the bumpers to report contact relative to the geometry of where they are placed on the robot, you can provide the x, y offsets of each bumper relative to the center of the robot (the center is the halfway point between the drive wheels).
translate(float, float) - Method in class lejos.robotics.navigation.Pose
Change the x and y coordinates of the pose by adding dx and dy.
travel(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Moves the NXT robot a specific distance in an (hopefully) straight line.
A positive distance causes forward motion, a negative distance moves backward.
travel(double) - Method in interface lejos.robotics.navigation.MoveController
Moves the NXT robot a specific distance.
travel(double, boolean) - Method in class lejos.robotics.navigation.DifferentialPilot
Moves the NXT robot a specific distance in an (hopefully) straight line.
A positive distance causes forward motion, a negative distance moves backward.
travel(double, boolean) - Method in interface lejos.robotics.navigation.MoveController
Moves the NXT robot a specific distance.
travel(float) - Method in class lejos.robotics.navigation.CompassPilot
Moves the NXT robot a specific distance;
A positive distance causes forward motion; negative distance moves backward.
travel(float, boolean) - Method in class lejos.robotics.navigation.CompassPilot
Moves the NXT robot a specific distance.
travelArc(double, double) - Method in interface lejos.robotics.navigation.ArcMoveController
Moves the NXT robot a specified distance along an arc of specified radius, after which the robot stops moving.
travelArc(double, double) - Method in class lejos.robotics.navigation.DifferentialPilot
 
travelArc(double, double, boolean) - Method in interface lejos.robotics.navigation.ArcMoveController
Moves the NXT robot a specified distance along an arc of specified radius, after which the robot stops moving.
travelArc(double, double, boolean) - Method in class lejos.robotics.navigation.DifferentialPilot
 
travelSpeed - Variable in class lejos.robotics.navigation.Move
 
turnRate(double) - Method in class lejos.robotics.navigation.DifferentialPilot
Calculates the turn rate corresponding to the turn radius;
use as the parameter for steer() negative argument means center of turn is on right, so angle of turn is negative
twoSigmaSquared - Variable in class lejos.robotics.localization.MCLParticleSet
 

U

update() - Method in class lejos.robotics.localization.MCLPoseProvider
Calls range scanner to get range readings, calculates the probabilities of each particle from the range readings and the map and calls resample(()
update(RangeReadings) - Method in class lejos.robotics.localization.MCLPoseProvider
Calculates particle weights from readings, then resamples the particle set;
updated - Variable in class lejos.robotics.localization.MCLPoseProvider
 
updatePose(Move) - Method in class lejos.robotics.localization.OdometryPoseProvider
 
updater - Variable in class lejos.robotics.localization.MCLPoseProvider
 
Updater() - Constructor for class lejos.robotics.localization.MCLPoseProvider.Updater
 

V

valueOf(String) - Static method in enum lejos.robotics.navigation.Move.MoveType
Returns the enum constant of this type with the specified name.
values() - Static method in enum lejos.robotics.navigation.Move.MoveType
Returns an array containing the constants of this enum type, in the order they are declared.
varH - Variable in class lejos.robotics.localization.MCLPoseProvider
 
varX - Variable in class lejos.robotics.localization.MCLPoseProvider
 
varY - Variable in class lejos.robotics.localization.MCLPoseProvider
 

W

waitComplete() - Method in class lejos.robotics.navigation.DifferentialPilot
wait for the current operation on both motors to complete
waitForActiveMove() - Method in class lejos.robotics.navigation.DifferentialPilot
 
waitForStop() - Method in class lejos.robotics.navigation.Navigator
Waits for the robot to stop for any reason ; returns true if the robot stopped at the final Waypoint of the path.
Waypoint - Class in lejos.robotics.navigation
A sequence of way points make up a route that a robot can navigate.
Waypoint(double, double) - Constructor for class lejos.robotics.navigation.Waypoint
 
Waypoint(double, double, double) - Constructor for class lejos.robotics.navigation.Waypoint
 
Waypoint(Point) - Constructor for class lejos.robotics.navigation.Waypoint
 
WaypointListener - Interface in lejos.robotics.navigation
Interface for informing listeners that a way point has been generated.
weight - Variable in class lejos.robotics.localization.MCLParticle
 
WHEEL_SIZE_EV3 - Static variable in interface lejos.robotics.navigation.MoveController
EV3 kit wheel diameter, in centimeters
WHEEL_SIZE_NXT1 - Static variable in interface lejos.robotics.navigation.MoveController
NXT 1.0 kit wheel diameter, in centimeters
WHEEL_SIZE_NXT2 - Static variable in interface lejos.robotics.navigation.MoveController
NXT 2.0 kit wheel diameter, in centimeters
WHEEL_SIZE_RCX - Static variable in interface lejos.robotics.navigation.MoveController
White RCX "motorcycle" wheel diameter, in centimeters
width - Variable in class lejos.robotics.mapping.OccupancyGridMap
 

X

x - Variable in class lejos.robotics.localization.OdometryPoseProvider
 
x - Variable in class lejos.robotics.pathfinding.Node
The x coordinate of this node.

Y

y - Variable in class lejos.robotics.localization.OdometryPoseProvider
 
y - Variable in class lejos.robotics.pathfinding.Node
The y coordinate of this node.

_

_acceleration - Variable in class lejos.robotics.navigation.DifferentialPilot
used by travel and rotate methods, and stop()
_angle - Variable in class lejos.robotics.navigation.DifferentialPilot
Angle about to turn - used by movementStopped
_blocked - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder
set by segmentBlocked() used by findPath()
_blocked - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
_blocked - Variable in class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
_candidate - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder
the set of nodes that are candidates for being in the shortest path, but whose distance from the start node is not yet known
_candidate - Variable in class lejos.robotics.pathfinding.ShortestPathFinder
the set of nodes that are candidates for being in the shortest path, but whose distance from the start node is not yet known.
_count - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder
 
_count - Variable in class lejos.robotics.pathfinding.ShortestPathFinder
 
_debug - Variable in class lejos.robotics.pathfinding.ShortestPathFinder
 
_destination - Variable in class lejos.robotics.navigation.Navigator
 
_destination - Variable in class lejos.robotics.pathfinding.ShortestPathFinder
 
_direction - Variable in class lejos.robotics.navigation.CompassPilot
 
_distance - Variable in class lejos.robotics.navigation.CompassPilot
 
_distance - Variable in class lejos.robotics.navigation.DifferentialPilot
Distance about to travel - used by movementStarted
_estimatedHeading - Variable in class lejos.robotics.navigation.CompassPilot
 
_heading - Variable in class lejos.robotics.localization.MCLPoseProvider
 
_heading - Variable in class lejos.robotics.navigation.CompassPilot
 
_heading - Variable in class lejos.robotics.navigation.Pose
 
_heading0 - Variable in class lejos.robotics.navigation.CompassPilot
 
_inside - Variable in class lejos.robotics.navigation.DifferentialPilot
The motor at the inside of the turn.
_interrupted - Variable in class lejos.robotics.navigation.Navigator
set by Stop, reset by followPath() , goTo() used by Nav.run(), callListeners
_iterations - Variable in class lejos.robotics.localization.MCLParticleSet
 
_keepGoing - Variable in class lejos.robotics.navigation.Navigator
frequently tested by Nav.run() to break out of primary control loop reset by stop(), and in Nav if _singleStep is set.
_left - Variable in class lejos.robotics.navigation.DifferentialPilot
Left motor..
_leftDegPerDistance - Variable in class lejos.robotics.navigation.DifferentialPilot
Left motor degrees per unit of travel.
_leftDirection - Variable in class lejos.robotics.navigation.DifferentialPilot
direction of rotation of left motor +1 or -1
_leftTC - Variable in class lejos.robotics.navigation.DifferentialPilot
 
_leftTurnRatio - Variable in class lejos.robotics.navigation.DifferentialPilot
Left motor revolutions for 360 degree rotation of robot (motors running in opposite directions).
_leftWheelDiameter - Variable in class lejos.robotics.navigation.DifferentialPilot
Diameter of left wheel.
_listeners - Variable in class lejos.robotics.navigation.DifferentialPilot
 
_listeners - Variable in class lejos.robotics.navigation.Navigator
 
_location - Variable in class lejos.robotics.navigation.Pose
 
_map - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder
The map of the obstacles
_map - Variable in class lejos.robotics.pathfinding.ShortestPathFinder
The map of the obstacles
_monitor - Variable in class lejos.robotics.navigation.DifferentialPilot
The monitor thread
_moveActive - Variable in class lejos.robotics.navigation.DifferentialPilot
set by rotatsionStopped() used by Monitor thread to call movementStopped()
_nav - Variable in class lejos.robotics.navigation.Navigator
 
_outside - Variable in class lejos.robotics.navigation.DifferentialPilot
The motor at the outside of the turn.
_p - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
_p - Variable in class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
_parity - Variable in class lejos.robotics.navigation.DifferentialPilot
Motor rotation forward makes robot move forward if parity == 1.
_path - Variable in class lejos.robotics.navigation.Navigator
 
_pilot - Variable in class lejos.robotics.navigation.Navigator
 
_pose - Variable in class lejos.robotics.navigation.Navigator
 
_predecessor - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
_predecessor - Variable in class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
_quickAcceleration - Variable in class lejos.robotics.navigation.DifferentialPilot
 
_radius - Variable in class lejos.robotics.navigation.Navigator
 
_reached - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder
the set of nodes that are candidates for being in the shortest path, and whose distance from the start node is known
_reached - Variable in class lejos.robotics.pathfinding.ShortestPathFinder
the set of nodes that are candidates for being in the shortest path, and whose distance from the start node is known
_right - Variable in class lejos.robotics.navigation.DifferentialPilot
Right motor.
_rightDegPerDistance - Variable in class lejos.robotics.navigation.DifferentialPilot
Right motor degrees per unit of travel.
_rightDirection - Variable in class lejos.robotics.navigation.DifferentialPilot
direction of rotation of right motor +1 or -1
_rightTC - Variable in class lejos.robotics.navigation.DifferentialPilot
 
_rightTurnRatio - Variable in class lejos.robotics.navigation.DifferentialPilot
Right motor revolutions for 360 degree rotation of robot (motors running in opposite directions).
_rightWheelDiameter - Variable in class lejos.robotics.navigation.DifferentialPilot
Diameter of right wheel.
_robotRotateSpeed - Variable in class lejos.robotics.navigation.DifferentialPilot
Speed of robot for turning in degree per seconds.
_robotTravelSpeed - Variable in class lejos.robotics.navigation.DifferentialPilot
Speed of robot for moving in wheel diameter units per seconds.
_sequenceNr - Variable in class lejos.robotics.navigation.Navigator
 
_singleStep - Variable in class lejos.robotics.navigation.Navigator
if true, causes Nav.run to break whenever waypoint is reached.
_source - Variable in class lejos.robotics.pathfinding.ShortestPathFinder
 
_sourceDistance - Variable in class lejos.robotics.pathfinding.DijkstraPathFinder.Node
 
_sourceDistance - Variable in class lejos.robotics.pathfinding.ShortestPathFinder.Node
 
_steerRatio - Variable in class lejos.robotics.navigation.DifferentialPilot
ratio of inside/outside motor speeds set by steer(turnRate) used by other steer methods;
_trackWidth - Variable in class lejos.robotics.navigation.DifferentialPilot
Distance between wheels.
_traveling - Variable in class lejos.robotics.navigation.CompassPilot
 
_turnRadius - Variable in class lejos.robotics.navigation.DifferentialPilot
 
_type - Variable in class lejos.robotics.navigation.DifferentialPilot
 
_x - Variable in class lejos.robotics.localization.MCLPoseProvider
 
_y - Variable in class lejos.robotics.localization.MCLPoseProvider
 
A B C D E F G H I K L M N O P Q R S T U V W X Y _