- 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_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
-
- 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
-
- 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
-
- 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
-
- 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
-
- _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
-