next up previous contents
Next: 7.4 amtecpowercube Up: 7. Device Drivers Previous: 7.2 acoustics   Contents

Subsections


7.3 amcl

Authors

Andrew Howard ahoward(at)usc.edu,Boyoon Jung boyoon(at)robotics.usc.edu

Synopsis

The amcl driver implements the Adaptive Monte-Carlo Localization algorithm described by Fox [2]. At the conceptual level, the amcl driver maintains a probability distribution over the set of all possible robot poses, and updates this distribution using data from odometry, sonar and/or laser range-finders. The driver also requires a pre-defined map of the environment against which to compare observed sensor values. At the implementation level, the amcl driver represents the probability distribution using a particle filter. The filter is ``adaptive'' because it dynamically adjusts the number of particles in the filter: when the robot's pose is highly uncertain, the number of particles is increased; when the robot's pose is well determined, the number of particles is decreased. The driver is therefore able make a trade-off between processing speed and localization accuracy.

As an example, consider the sequence of images shown in Figure 7.1. This sequence shows the filter converging from an initial configuration in which the pose of the robot is entirely unknown to a final configuration in which the pose of the robot is well determined. At the same time, the number of particles in the filter decreases from 100,000 to less than 100.

The amcl driver has the some of the usual features - and failures - associated with simple Monte-Carlo Localization techniques:

The amcl driver also has some slightly unusual temporal behavior:

Figure 7.1: Snap-shots showing the amcl driver in action; convergence in this case is relatively slow.
\begin{figure*}\begin{center}
\begin{tabular}{cc}
\epsfig{height=4cm,file=driver...
... $t = 120$~sec, $\approx 100$\ particles
\end{tabular}
\end{center}\end{figure*}

Caveats

At the time of writing, this driver is still evolving. The sensor models, in particular, are currently over-simplified and under-parameterized (there are lots of magic numbers lurking about the place). Consequently, while this driver is known to work for certain hardware configurations (think Pioneer2DX with a SICKLMS200 laser range-finder), other configurations may require some refinement of the sensor models.

Interfaces

Supported interfaces:

Required devices:

Supported configuration requests:

Configuration file options

Name Type Default Meaning

position_index
integer 0 Index of the position device to use (this will usually be an odometric device of some sort).

sonar_index
integer -1 Index of the sonar ranging device to use; set this to -1 if you dont wish to use sonar.

laser_index
integer -1 Index of the laser ranging device to use; set this to -1 if you dont wish to use laser.

wifi_index
integer -1 Index of the WiFi signal-strength device to use; set this to -1 if you dont wish to use WiFi signal-strength.

map_file
filename NULL Name of the file containing the occupancy map; see notes below for more on the map format.

map_scale
length 0.05 Scale of the map (meters/pixel).

map_negate
integer 0 Invert the states in the map (occupied becomes empty and empty becomes occupied); see notes below.

robot_radius
length 0.20 Effective radius of the robot (meters); this value will be used to eliminate hypotheses that imply that the robot is co-located with an obstacle.

laser_max_samples
integer 5 The maximum number of laser range readings to use when updating the filter.

wifi_beacon_N
tuple none A tuple + [ "hostname" "mapfilename" ]+ describing the Nth WiFi beacon. hostname specifies the name or IP address of the beacon; mapfilename points to the WiFi signal strength map for this beacon.

pf_min_samples
integer 100 Lower bound on the number of samples to maintain in the particle filter.

pf_max_samples
integer 10000 Upper bound on the number of samples to maintain in the particle filter.

pf_err
float 0.01 Control parameter for the particle set size. See notes below.

pf_z
float 3 Control parameter for the particle set size. See notes below.

init_pose
vector [0 0 0] Initial pose estimate (mean value) for the robot (meters, meters, degrees).

init_pose_var
vector [103103102] Uncertainty in the initial pose estimate (meters, meters, degrees).

enable_gui
integer 0 Set this to 1 to enable the built-in driver GUI (useful for debugging). Player must also be build with configure -enable-rtkgui for this option to have any effect.

Notes

Example: Using the amcl driver with a Pioneer robot

The following configuration file illustrates the use of the amcl driver on a Pioneer robot equipped with a SICK LMS200 scanning laser range finder:

  position:0 
  (
     driver "p2os_position" 
     port "/dev/ttyS1"
  )
  
  laser:0 
  (
    driver "sicklms200" 
    port "/dev/ttyS2"
  )

  localize:0 
  (
    driver "amcl"
    position_index 0
    laser_index 0
    map_file "mymap.pgm"
    map_scale 0.05
  )
Naturally, the port, map_file and map_scale values should be changed to match your particular configuration.

Example: Using the amcl driver with Stage

The amcl driver is not supported natively in Stage. Users must therefore employ a second Player server configured to use the passthrough driver (see Section 7.31). The basic procedure is as follows.

Example: Using WiFi signal strength

TODO


next up previous contents
Next: 7.4 amtecpowercube Up: 7. Device Drivers Previous: 7.2 acoustics   Contents
2004-06-02