next up previous
Next: Precision and Performance Up: Experimental Results Previous: Localization in Incomplete Maps

Localization in Occupancy Grid Maps Using Sonar

 

The next experiment described here is carried out based on data collected with the mobile robot Rhino during the 1994 AAAI mobile robot competition [Simmons1995]. Figure 16(a) shows an occupancy grid map [Moravec & Elfes1985, Moravec1988] of the environment, constructed with the techniques described in [Thrun et al. 1998a, Thrun1998b]. The size of the map is tex2html_wrap_inline3519 , and the grid resolution is 15cm.

  figure1843

Figure 16(b) shows a trajectory of the robot along with measurements of the 24 ultrasound sensors obtained as the robot moved through the competition arena. Here we use this sensor information to globally localize the robot from scratch. The time required to process this data on a 400MHz Pentium II is 80 seconds, using a position probability grid with an angular resolution of 3 degrees. Please note that this is exactly the time needed by the robot to traverse this trajectory; thus, our approach works in real-time. Figure 16(b) also marks positions of the robot after perceiving 5 (A), 18 (B), and 24 (C) sensor sweeps. The belief states during global localization at these three points in time are illustrated in Figure 17.

  figure1873

The figures show the belief of the robot projected onto the tex2html_wrap_inline2963 -plane by plotting for each tex2html_wrap_inline2963 -position the maximum probability over all possible orientations. More likely positions are darker and for illustration purposes, Figures 17(a) and 17(b) use a logarithmic scale in intensity. Figure 17(a) shows the belief state after integrating 5 sensor sweeps (see also position A in Figure 16(b)). At this point in time, all the robot knows is that it is in one of the corridors of the environment. After integrating 18 sweeps of the ultrasound sensors, the robot is almost certain that it is at the end of a corridor (compare position B in Figures 16(b) and 17(b)). A short time later, after turning left and integrating six more sweeps of the ultrasound ring, the robot has determined its position uniquely. This is represented by the unique peak containing 99% of the whole probability mass in Figure 17(c).

  figure1906

Figure 18 illustrates the ability of Markov localization to correct accumulated dead-reckoning errors by matching ultrasound data with occupancy grid maps. Figure 18(a) shows a typical 240m long trajectory, measured by Rhino's wheel-encoders in the 1994 AAAI mobile robot competition arena. Obviously, the rotational error of the odometry quickly increases. Already after traveling 40m, the accumulated error in the orientation (raw odometry) is about 50 degrees. Figure 18(b) shows the path of the robot estimated by Markov localization, which is significantly more correct.


next up previous
Next: Precision and Performance Up: Experimental Results Previous: Localization in Incomplete Maps

Dieter Fox
Fri Nov 19 14:29:33 MET 1999