Improving Computational and Memory Requirements of Simultaneous Localiza- tion and Map Building Algorithms Jose Guivant, Eduardo Nebot* Australian Centre for Field Robotics The University of Sydney, NSW 2006, Australia * Also with the CRC CMTE Centre for Mining, Technology and Equipment jguivant/nebot @acfr.usyd.edu.au Abstract This paper addresses the problem of implementing simul- taneous localisation and map building (SLAM) in very large outdoor environments. A method is presented to reduce the computational requirement from ~O(N 2 ) to ~O(N), being N the states used to represent all the land- marks and vehicle pose. With this implementation the memory requirement are also reduced to ~O(N). This al- gorithm presents an efficient solution to the full update required by the Compressed Extended Kalman Filter algo- rithm (CEKF). Experimental results are also presented. 1 Introduction The problem of localization when a map of the environ- ment is available has been solved before with very effi- cient algorithms [1] [2]. Similarly, there are well proven techniques for the generation of environment maps using observations obtained from known locations [3]. There are also successful real-time implementations of localiza- tion loops based on Bayesian approaches [4]. A more challenging problem is the solution of both posi- tion and localisation at the same time. This problem is called “simultaneous localization and map building” (SLAM) [5],[6] and “Concurrent Map and Localisation” (CML) [7]. Optimal SLAM approaches based on Bayesian filtering with non-Gaussian assumptions are extremely expensive making them difficult to apply in real time. Nevertheless these methods present some significant advantages such as the inherent solution of the data association problem. In fact they can address the localization problem starting at a completely unknown position and to solve the “kidnapped robot” problem, that is a robot that is suddenly moved to another position without being told. Some approaches based on these techniques [2], approximate the probability representation using samples of the probability density distribution. Efforts to apply these techniques in real time are started to appear. In [8] and [9] a Sum of Gaussian (SOG) distribution is used to build a feature map of land- marks to represent the environment and its application to the full-Bayesian SLAM problem is presented. It is also argued that the SOG method provides a computationally tractable implementation of the full Bayes SLAM. There are several optimal and sub-optimal techniques that are attractive to solve SLAM in real time, most of them based on the Extended Kalman Filter (EKF) framework, [7],[10] and [11]. These techniques assume Gaussian or at least uni-modal density probability distributions. The ma- jor problems of EKF implementations are: 1. The estimation must always have an uni-modal, more strictly a Gaussian, probability distribution. 2. Revisits to known places and external absolute observa- tions such as GPS measurement can produce ‘strong’ up- dates, generating incorrect corrections. 3. A large number of map objects will quadratically in- crease the memory and computational power require- ments. The first two limitations can be overcome by using Hybrid combinations of EKF and non-Gaussian Bayesian filters [12]. The non-Gaussian strategy is applied in the initiali- sation phase or at any stage when the probability distribu- tion can not be uni-modally approximated, that is when the data association is not possible. In this case the EKF based system will be in fault since the high uncertainty prevents the data association making impossible the in- corporation of the observation using the EKF update. Un- der this condition the usage of those observations will generate multi-hypotheses in the estimations. In [12], the Bayesian estimator is used until sufficient information is obtained to collapse all the multi-hypotheses in a unique uni-modal distribution that the normal EKF filter is able to use. The third item addresses the computation and memory requirement of full SLAM. It is well known that this algo- rithm has computational requirements of ~O(N 2 ), being N the states used to represent all the landmarks and vehicle pose. In [5] the Compressed EKF (CEKF) was intro- duced. This algorithm dramatically reduces the computa- tional requirements of SLAM while generating equivalent results to the full standard implementation. This algorithm represents a remarkable improvement when the vehicle operates in a local area. Still a full SLAM update is re- quired when a transition to a different area is made. Another aspect that has not been addressed is the memory requirement. A system with 10000 states will require up to 800 Mb to maintain the covariance of the states. Both memory and global update calculation have a cost of order ~O(N 2 ) as stated before. When using the CEKF the cost in 2731 0-7803-7272-7/02/$17.00 ' 2002 IEEE Proceedings of the 2002 IEEE International Conference on Robotics & Automation Washington, DC May 2002