lobot::FastSLAM Class Reference

An implementation of the grid-based FastSLAM algorithm. More...

#include <Robots/LoBot/slam/LoFastSLAM.H>

Collaboration diagram for lobot::FastSLAM:
Collaboration graph
[legend]

List of all members.

Public Member Functions

 FastSLAM (const LRFData &)
 FastSLAM (const LRFData &, const boost::shared_ptr< OccGrid > &)
void update (const Odometry &, const LRFData &)
std::vector< Particle::Vizviz () const
 ~FastSLAM ()
 Clean-up.

OccGrid current_map () const
Pose current_pose () const

Detailed Description

An implementation of the grid-based FastSLAM algorithm.

This class implements the FastSLAM algorithm for building an occupancy grid map while simultaneously localizing the robot within this map.

Definition at line 76 of file LoFastSLAM.H.


Constructor & Destructor Documentation

lobot::FastSLAM::FastSLAM ( const LRFData lrf  ) 

In the grid-based version of FastSLAM, each particle needs to carry its own copy of the occupancy map being built. As this can result in a rather large computational and memory burden, it is crucial to reduce the total number of particles required to effectively perform the SLAM operation.

One way to do that is to eschew raw odometry in favour of something more precise such as 2D scan matching based on laser range finder measurements. The Robolocust implementation of FastSLAM does in fact use scan matching.

Therefore, during initialization, the client must supply an initial LRF scan.

Definition at line 113 of file LoFastSLAM.C.

References lobot::SlamParams::num_particles().

lobot::FastSLAM::FastSLAM ( const LRFData lrf,
const boost::shared_ptr< OccGrid > &  known_map 
)

This implementation of FastSLAM can be configured to forgo the mapping operation and perform localization only. In that case, the user must supply a known occupancy grid map, which will be used to exercise the Monte Carlo Localization component of FastSLAM.

This constructor is identical to the previous one except that it expects to be given a known map for localization only mode.

Definition at line 123 of file LoFastSLAM.C.

References lobot::SlamParams::num_particles().

lobot::FastSLAM::~FastSLAM (  ) 

Clean-up.

Definition at line 572 of file LoFastSLAM.C.


Member Function Documentation

OccGrid lobot::FastSLAM::current_map (  )  const

As mentioned earlier, in grid-based FastSLAM, each particle carries its own copy of both the occupancy map being built as well as the robot's current pose. These methods return the current best hypothesis of the actual map or pose by applying a robust mean procedure that works like so:

First, we find the particle with maximum weight. Then, we find the K particles whose states most closely match that of the max particle. The final state is computed as the average of these K states.

NOTE: K is specified in the Robolocust config file as a percentage of the total number of particles.

Definition at line 543 of file LoFastSLAM.C.

void lobot::FastSLAM::update ( const Odometry ut,
const LRFData zt 
)

This method updates the occupancy map and current pose given the latest (raw) odometry (i.e., control input) and LRF readings (i.e., sensor data).

Definition at line 219 of file LoFastSLAM.C.

References lobot::SlamParams::ess_threshold(), max(), and lobot::Particle::randomize().

std::vector< Particle::Viz > lobot::FastSLAM::viz (  )  const

Visualization support: return a list of Particle::Viz structures so that the client knows the current pose hypotheses and their corresponding weights.

Definition at line 561 of file LoFastSLAM.C.

References transform(), and lobot::Particle::viz().


The documentation for this class was generated from the following files:
Generated on Sun May 8 08:44:30 2011 for iLab Neuromorphic Vision Toolkit by  doxygen 1.6.3