diff -up ./libs/maps/src/maps/CColouredOctoMap.cpp.octomap18 ./libs/maps/src/maps/CColouredOctoMap.cpp --- ./libs/maps/src/maps/CColouredOctoMap.cpp.octomap18 2016-08-14 11:22:59.558177427 -0400 +++ ./libs/maps/src/maps/CColouredOctoMap.cpp 2016-08-14 11:23:28.697317833 -0400 @@ -195,7 +195,7 @@ bool CColouredOctoMap::internal_insertOb } // Insert rays: - m_octomap.insertScan(scan, sensorPt, insertionOptions.maxrange, insertionOptions.pruning); + m_octomap.insertPointCloud(scan, sensorPt, insertionOptions.maxrange, insertionOptions.pruning); return true; } else if ( IS_CLASS(obs,CObservation3DRangeScan) ) diff -up ./libs/maps/src/maps/COctoMap.cpp.octomap18 ./libs/maps/src/maps/COctoMap.cpp --- ./libs/maps/src/maps/COctoMap.cpp.octomap18 2016-08-14 11:23:14.514762777 -0400 +++ ./libs/maps/src/maps/COctoMap.cpp 2016-08-14 11:23:50.425168188 -0400 @@ -151,7 +151,7 @@ bool COctoMap::internal_insertObservatio if (!internal_build_PointCloud_for_observation(obs,robotPose, sensorPt, scan)) return false; // Nothing to do. // Insert rays: - m_octomap.insertScan(scan, sensorPt, insertionOptions.maxrange, insertionOptions.pruning); + m_octomap.insertPointCloud(scan, sensorPt, insertionOptions.maxrange, insertionOptions.pruning); return true; }