Brian and Giorgio, Thank you for the replies so far. I resolved the pose history issue. However I am running into some different problems at the moment. I have already contacted Giorgio about this issue. I am including a more detailed explanation this time. This loop in the ROS driver I am using is responsible for building the map before publishing it. It builds it by iterating up the node tree: GMapping::ScanMatcherMap smap(center, xmin_, ymin_, xmax_, ymax_, delta_); for(GMapping::GridSlamProcessor::TNode* n = best.node; n; n = n->parent) { if(!n->reading) { ROS_DEBUG("Reading is NULL"); continue; } matcher.invalidateActiveArea(); matcher.computeActiveArea(smap, n->pose, &((*n->reading)[0])); matcher.registerScan(smap, n->pose, &((*n->reading)[0])); } However, the execution time of this loop grows linearly with the runtime of the program. I am assuming this is because the depth of the node tree grows as well. I am attaching output of the slam_gmapping node to show the execution time of the loop. The two logs are taken using this .bag file: http://pr.willowgarage.com/data/gmapping/basic_localization_stage.bag The two test runs are with slightly different parameters (included in the top of the log file.) You will see that the execution time starts at less than 100 ms, and steadily increases up to 3 seconds, over the course of 90 seconds. The only time the value drops significantly is right at the end of the bag file, when no more data is being sent.You will notice that even after resampling, the time remains 1-2 seconds. While 1-2 seconds does not sound bad, I assume that this will only get worse, since it grows linearly with the number of scans processed. We are using the gmapping package to perform odometry-free slam on a quadrotor micro-UAV. We've had good success so far. However, when we hit the map update step, and it takes 3+ seconds to perform that operation, it really throws off the scan matcher. Giorgio has informed me that it is not necessary to iterate over the tree in order to get the map. In fact, I'm told I should be able to get the map simply by doing GMapping::GridSlamProcessor::Particle best = gsp_->getParticles()[gsp_->getBestParticleIndex()]; GMapping::ScanMatcherMap smap = best.map; I had some limited success in implementing this inside the ROS driver, but it doesn't really work correctly. My guess is that there are extra functions that need to be called for invalidating/re-calculating the size of the map, but I don't know exactly what and where. Thanks, Ivan Dryanovski