|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Object lejos.navigation.SimpleNavigator lejos.localization.TachoLocalizer
public abstract class TachoLocalizer
An abstract extension to TachoNavigator that uses a map and a set of particles to implement the Monte Carlo Localization algorithm to estimate the pose of the robot as it moves about. Note that the navigator uses its own local coordinates relative to the robot's starting position, whereas the estimated pose is in global coordinates, as used by the map. This class must be extended and the takeReadings method implemented. Note that only travel and rotate methods update the particle set.
Field Summary | |
---|---|
protected float |
angle
|
protected float |
distance
|
protected Map |
map
|
protected Move |
mv
|
protected int |
numParticles
|
protected int |
numReadings
|
protected ParticleSet |
particles
|
protected float |
projection
|
protected RangeReadings |
readings
|
Constructor Summary | |
---|---|
TachoLocalizer(Map map,
int numParticles,
int numReadings,
float wheelDiameter,
float trackWidth,
Motor leftMotor,
Motor rightMotor,
float projection,
boolean reverse)
|
Method Summary | |
---|---|
Pose |
getEstimatedPose()
Get the estimated position and angle of the robot. |
Map |
getMap()
Get the map |
ParticleSet |
getParticles()
Get the particle set |
float |
getProjection()
Get the forward projection of the robot |
RangeReadings |
getReadings()
Return readings |
int |
numParticles()
Get the number of particles |
void |
rotate(float angle,
boolean immediateReturn)
Rotates the NXT robot a specific number of degrees in a direction (+ or -). |
abstract void |
takeReadings()
Take a set of readings to the nearest map features |
void |
travel(float distance,
boolean immediateReturn)
Moves the NXT robot a specific distance. |
void |
updatePosition()
Update the robot position and apply it to all the particles. |
Methods inherited from class lejos.navigation.SimpleNavigator |
---|
angleTo, backward, distanceTo, forward, getAngle, getPilot, getX, getY, goTo, goTo, isMoving, rotate, rotateLeft, rotateRight, rotateTo, rotateTo, setMoveSpeed, setPosition, setSpeed, setTurnSpeed, stop, travel, turn, turn, turn |
Methods inherited from class java.lang.Object |
---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
Methods inherited from interface lejos.navigation.Navigator |
---|
angleTo, backward, distanceTo, forward, getAngle, getX, getY, goTo, goTo, isMoving, rotate, rotateLeft, rotateRight, rotateTo, rotateTo, setMoveSpeed, setPosition, setTurnSpeed, stop, travel |
Field Detail |
---|
protected RangeReadings readings
protected float projection
protected Map map
protected int numParticles
protected ParticleSet particles
protected float angle
protected float distance
protected Move mv
protected int numReadings
Constructor Detail |
---|
public TachoLocalizer(Map map, int numParticles, int numReadings, float wheelDiameter, float trackWidth, Motor leftMotor, Motor rightMotor, float projection, boolean reverse)
Method Detail |
---|
public abstract void takeReadings()
Localizer
takeReadings
in interface Localizer
public void rotate(float angle, boolean immediateReturn)
SimpleNavigator
rotate
in interface Navigator
rotate
in class SimpleNavigator
angle
- Angle to rotate in degrees. A positive value rotates left, a negative value right.immediateReturn
- iff true, the method returns immediately, in which case the programmer public void travel(float distance, boolean immediateReturn)
SimpleNavigator
travel
in interface Navigator
travel
in class SimpleNavigator
distance
- The positive or negative distance to move the robot, same units as _wheelDiameterimmediateReturn
- iff true, the method returns immediately, in which case the programmer public void updatePosition()
updatePosition
in interface Navigator
updatePosition
in class SimpleNavigator
public float getProjection()
public int numParticles()
public ParticleSet getParticles()
public Map getMap()
public Pose getEstimatedPose()
getEstimatedPose
in interface Localizer
public RangeReadings getReadings()
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |