33 using octomap_msgs::Octomap;
 
   35 bool is_equal (
double a, 
double b, 
double epsilon = 1.0e-7)
 
   37     return std::abs(a - b) < 
epsilon;
 
   44   m_nh_private(private_nh_),
 
   45   m_pointCloudSub(NULL),
 
   46   m_tfPointCloudSub(NULL),
 
   47   m_reconfigureServer(m_config_mutex, private_nh_),
 
   51   m_worldFrameId(
"/map"), m_baseFrameId(
"base_footprint"),
 
   53   m_useColoredMap(false),
 
   55   m_latchedTopics(true),
 
   56   m_publishFreeSpace(false),
 
   60   m_pointcloudMinX(-
std::numeric_limits<double>::
max()),
 
   61   m_pointcloudMaxX(
std::numeric_limits<double>::
max()),
 
   62   m_pointcloudMinY(-
std::numeric_limits<double>::
max()),
 
   63   m_pointcloudMaxY(
std::numeric_limits<double>::
max()),
 
   64   m_pointcloudMinZ(-
std::numeric_limits<double>::
max()),
 
   65   m_pointcloudMaxZ(
std::numeric_limits<double>::
max()),
 
   66   m_occupancyMinZ(-
std::numeric_limits<double>::
max()),
 
   67   m_occupancyMaxZ(
std::numeric_limits<double>::
max()),
 
   68   m_minSizeX(0.0), m_minSizeY(0.0),
 
   69   m_filterSpeckles(false), m_filterGroundPlane(false),
 
   70   m_groundFilterDistance(0.04), m_groundFilterAngle(0.15), m_groundFilterPlaneDistance(0.07),
 
   72   m_incrementalUpdate(false),
 
   75   double probHit, probMiss, thresMin, thresMax;
 
  115     ROS_WARN_STREAM(
"You enabled ground filtering but incoming pointclouds will be pre-filtered in [" 
  117               << 
"This will not work.");
 
  121     ROS_WARN_STREAM(
"You enabled both height map and RGB color registration. This is contradictory. Defaulting to height map.");
 
  126 #ifdef COLOR_OCTOMAP_SERVER 
  127     ROS_INFO_STREAM(
"Using RGB color registration (if information available)");
 
  129     ROS_ERROR_STREAM(
"Colored map requested in launch file - node not running/compiled to support colors, please define COLOR_OCTOMAP_SERVER and recompile or launch the octomap_color_server node");
 
  166     ROS_INFO(
"Publishing latched (single publish will take longer, all topics are prepared)");
 
  168     ROS_INFO(
"Publishing non-latched (topics are only prepared as needed, will only be re-published on map change");
 
  186   dynamic_reconfigure::Server<OctomapServerConfig>::CallbackType 
f;
 
  211   if (filename.length() <= 3)
 
  214   std::string suffix = filename.substr(filename.length()-3, 3);
 
  219   } 
else if (suffix == 
".ot"){
 
  230       ROS_ERROR(
"Could not read OcTree in file, currently there are no other types supported in .ot");
 
  244   double minX, minY, minZ;
 
  245   double maxX, maxY, maxZ;
 
  277     ROS_ERROR_STREAM( 
"Transform error of sensor data: " << ex.what() << 
", quitting callback");
 
  281   Eigen::Matrix4f sensorToWorld;
 
  286   pcl::PassThrough<PCLPoint> pass_x;
 
  287   pass_x.setFilterFieldName(
"x");
 
  289   pcl::PassThrough<PCLPoint> pass_y;
 
  290   pass_y.setFilterFieldName(
"y");
 
  292   pcl::PassThrough<PCLPoint> pass_z;
 
  293   pass_z.setFilterFieldName(
"z");
 
  308       ROS_ERROR_STREAM( 
"Transform error for ground plane filter: " << ex.what() << 
", quitting callback.\n" 
  309                         "You need to set the base_frame_id or disable filter_ground.");
 
  313     Eigen::Matrix4f sensorToBase, baseToWorld;
 
  318     pcl::transformPointCloud(pc, pc, sensorToBase);
 
  319     pass_x.setInputCloud(pc.makeShared());
 
  321     pass_y.setInputCloud(pc.makeShared());
 
  323     pass_z.setInputCloud(pc.makeShared());
 
  328     pcl::transformPointCloud(pc_ground, pc_ground, baseToWorld);
 
  329     pcl::transformPointCloud(pc_nonground, pc_nonground, baseToWorld);
 
  332     pcl::transformPointCloud(pc, pc, sensorToWorld);
 
  335     pass_x.setInputCloud(pc.makeShared());
 
  337     pass_y.setInputCloud(pc.makeShared());
 
  339     pass_z.setInputCloud(pc.makeShared());
 
  344     pc_ground.header = pc.header;
 
  345     pc_nonground.header = pc.header;
 
  352   ROS_DEBUG(
"Pointcloud insertion in OctomapServer done (%zu+%zu pts (ground/nonground), %f sec)", pc_ground.size(), pc_nonground.size(), total_elapsed);
 
  358   point3d sensorOrigin = pointTfToOctomap(sensorOriginTf);
 
  366 #ifdef COLOR_OCTOMAP_SERVER 
  367   unsigned char* colors = 
new unsigned char[3];
 
  371   KeySet free_cells, occupied_cells;
 
  373   for (PCLPointCloud::const_iterator it = ground.begin(); it != ground.end(); ++it){
 
  374     point3d point(it->x, it->y, it->z);
 
  380       point = sensorOrigin + (point - sensorOrigin).normalized() * 
m_maxRange;
 
  398   for (PCLPointCloud::const_iterator it = nonground.begin(); it != nonground.end(); ++it){
 
  399     point3d point(it->x, it->y, it->z);
 
  413         occupied_cells.insert(key);
 
  418 #ifdef COLOR_OCTOMAP_SERVER // NB: Only read and interpret color if it's an occupied node 
  419         m_octree->averageNodeColor(it->x, it->y, it->z, it->r, it->g, it->b);
 
  423       point3d new_end = sensorOrigin + (point - sensorOrigin).normalized() * 
m_maxRange;
 
  429           free_cells.insert(endKey);
 
  442   for(KeySet::iterator it = free_cells.begin(), end=free_cells.end(); it!= end; ++it){
 
  443     if (occupied_cells.find(*it) == occupied_cells.end()){
 
  449   for (KeySet::iterator it = occupied_cells.begin(), end=occupied_cells.end(); it!= end; it++) {
 
  480 #ifdef COLOR_OCTOMAP_SERVER 
  501   if (octomapSize <= 1){
 
  502     ROS_WARN(
"Nothing to publish, octree is empty");
 
  513   visualization_msgs::MarkerArray freeNodesVis;
 
  517   geometry_msgs::Pose pose;
 
  521   visualization_msgs::MarkerArray occupiedNodesVis;
 
  526   pcl::PointCloud<PCLPoint> pclCloud;
 
  543       double z = it.getZ();
 
  544       double half_size = it.getSize() / 2.0;
 
  547         double size = it.getSize();
 
  548         double x = it.getX();
 
  549         double y = it.getY();
 
  550 #ifdef COLOR_OCTOMAP_SERVER 
  551         int r = it->getColor().r;
 
  552         int g = it->getColor().g;
 
  553         int b = it->getColor().b;
 
  558           ROS_DEBUG(
"Ignoring single speckle at (%f,%f,%f)", x, y, z);
 
  568         if (publishMarkerArray){
 
  569           unsigned idx = it.getDepth();
 
  570           assert(idx < occupiedNodesVis.markers.size());
 
  572           geometry_msgs::Point cubeCenter;
 
  577           occupiedNodesVis.markers[idx].points.push_back(cubeCenter);
 
  579             double minX, minY, minZ, maxX, maxY, maxZ;
 
  584             occupiedNodesVis.markers[idx].colors.push_back(
heightMapColor(h));
 
  587 #ifdef COLOR_OCTOMAP_SERVER 
  589             std_msgs::ColorRGBA _color; _color.r = (r / 255.); _color.g = (g / 255.); _color.b = (b / 255.); _color.a = 1.0; 
 
  590             occupiedNodesVis.markers[idx].colors.push_back(_color);
 
  596         if (publishPointCloud) {
 
  597 #ifdef COLOR_OCTOMAP_SERVER 
  599           _point.x = x; _point.y = y; _point.z = z;
 
  600           _point.r = r; _point.g = g; _point.b = b;
 
  601           pclCloud.push_back(_point);
 
  603           pclCloud.push_back(
PCLPoint(x, y, z));
 
  609       double z = it.getZ();
 
  610       double half_size = it.getSize() / 2.0;
 
  618           double x = it.getX();
 
  619           double y = it.getY();
 
  622           if (publishFreeMarkerArray){
 
  623             unsigned idx = it.getDepth();
 
  624             assert(idx < freeNodesVis.markers.size());
 
  626             geometry_msgs::Point cubeCenter;
 
  631             freeNodesVis.markers[idx].points.push_back(cubeCenter);
 
  643   if (publishMarkerArray){
 
  644     for (
unsigned i= 0; i < occupiedNodesVis.markers.size(); ++i){
 
  648       occupiedNodesVis.markers[i].header.stamp = rostime;
 
  649       occupiedNodesVis.markers[i].ns = 
"map";
 
  650       occupiedNodesVis.markers[i].id = i;
 
  651       occupiedNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
 
  652       occupiedNodesVis.markers[i].scale.x = size;
 
  653       occupiedNodesVis.markers[i].scale.y = size;
 
  654       occupiedNodesVis.markers[i].scale.z = size;
 
  656         occupiedNodesVis.markers[i].color = 
m_color;
 
  659       if (occupiedNodesVis.markers[i].points.size() > 0)
 
  660         occupiedNodesVis.markers[i].action = visualization_msgs::Marker::ADD;
 
  662         occupiedNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
 
  670   if (publishFreeMarkerArray){
 
  671     for (
unsigned i= 0; i < freeNodesVis.markers.size(); ++i){
 
  675       freeNodesVis.markers[i].header.stamp = rostime;
 
  676       freeNodesVis.markers[i].ns = 
"map";
 
  677       freeNodesVis.markers[i].id = i;
 
  678       freeNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
 
  679       freeNodesVis.markers[i].scale.x = size;
 
  680       freeNodesVis.markers[i].scale.y = size;
 
  681       freeNodesVis.markers[i].scale.z = size;
 
  685       if (freeNodesVis.markers[i].points.size() > 0)
 
  686         freeNodesVis.markers[i].action = visualization_msgs::Marker::ADD;
 
  688         freeNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
 
  696   if (publishPointCloud){
 
  697     sensor_msgs::PointCloud2 cloud;
 
  700     cloud.header.stamp = rostime;
 
  704   if (publishBinaryMap)
 
  712   ROS_DEBUG(
"Map publishing in OctomapServer took %f sec", total_elapsed);
 
  716                                     OctomapSrv::Response &res)
 
  719   ROS_INFO(
"Sending binary map data on service request");
 
  726   ROS_INFO(
"Binary octomap sent in %f sec", total_elapsed);
 
  731                                     OctomapSrv::Response &res)
 
  733   ROS_INFO(
"Sending full map data on service request");
 
  745   point3d min = pointMsgToOctomap(req.min);
 
  764   visualization_msgs::MarkerArray occupiedNodesVis;
 
  783   for (std::size_t i = 0; i < occupiedNodesVis.markers.size(); ++i){
 
  785     occupiedNodesVis.markers[i].header.stamp = rostime;
 
  786     occupiedNodesVis.markers[i].ns = 
"map";
 
  787     occupiedNodesVis.markers[i].id = i;
 
  788     occupiedNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
 
  789     occupiedNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
 
  793   visualization_msgs::MarkerArray freeNodesVis;
 
  795   for (std::size_t i = 0; i < freeNodesVis.markers.size(); ++i){
 
  797     freeNodesVis.markers[i].header.stamp = rostime;
 
  798     freeNodesVis.markers[i].ns = 
"map";
 
  799     freeNodesVis.markers[i].id = i;
 
  800     freeNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
 
  801     freeNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
 
  812   map.header.stamp = rostime;
 
  824   map.header.stamp = rostime;
 
  835   ground.header = pc.header;
 
  836   nonground.header = pc.header;
 
  839     ROS_WARN(
"Pointcloud in OctomapServer too small, skipping ground plane extraction");
 
  843     pcl::ModelCoefficients::Ptr coefficients (
new pcl::ModelCoefficients);
 
  844     pcl::PointIndices::Ptr inliers (
new pcl::PointIndices);
 
  847     pcl::SACSegmentation<PCLPoint> seg;
 
  848     seg.setOptimizeCoefficients (
true);
 
  850     seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
 
  851     seg.setMethodType(pcl::SAC_RANSAC);
 
  852     seg.setMaxIterations(200);
 
  854     seg.setAxis(Eigen::Vector3f(0,0,1));
 
  860     pcl::ExtractIndices<PCLPoint> extract;
 
  861     bool groundPlaneFound = 
false;
 
  863     while(cloud_filtered.size() > 10 && !groundPlaneFound){
 
  864       seg.setInputCloud(cloud_filtered.makeShared());
 
  865       seg.segment (*inliers, *coefficients);
 
  866       if (inliers->indices.size () == 0){
 
  867         ROS_INFO(
"PCL segmentation did not find any plane.");
 
  872       extract.setInputCloud(cloud_filtered.makeShared());
 
  873       extract.setIndices(inliers);
 
  876         ROS_DEBUG(
"Ground plane found: %zu/%zu inliers. Coeff: %f %f %f %f", inliers->indices.size(), cloud_filtered.size(),
 
  877                   coefficients->values.at(0), coefficients->values.at(1), coefficients->values.at(2), coefficients->values.at(3));
 
  878         extract.setNegative (
false);
 
  879         extract.filter (ground);
 
  883         if(inliers->indices.size() != cloud_filtered.size()){
 
  884           extract.setNegative(
true);
 
  886           extract.filter(cloud_out);
 
  887           nonground += cloud_out;
 
  888           cloud_filtered = cloud_out;
 
  891         groundPlaneFound = 
true;
 
  893         ROS_DEBUG(
"Horizontal plane (not ground) found: %zu/%zu inliers. Coeff: %f %f %f %f", inliers->indices.size(), cloud_filtered.size(),
 
  894                   coefficients->values.at(0), coefficients->values.at(1), coefficients->values.at(2), coefficients->values.at(3));
 
  895         pcl::PointCloud<PCLPoint> cloud_out;
 
  896         extract.setNegative (
false);
 
  897         extract.filter(cloud_out);
 
  898         nonground +=cloud_out;
 
  905         if(inliers->indices.size() != cloud_filtered.size()){
 
  906           extract.setNegative(
true);
 
  907           cloud_out.points.clear();
 
  908           extract.filter(cloud_out);
 
  909           cloud_filtered = cloud_out;
 
  911           cloud_filtered.points.clear();
 
  917     if (!groundPlaneFound){ 
 
  918       ROS_WARN(
"No ground plane found in scan");
 
  921       pcl::PassThrough<PCLPoint> second_pass;
 
  922       second_pass.setFilterFieldName(
"z");
 
  924       second_pass.setInputCloud(pc.makeShared());
 
  925       second_pass.filter(ground);
 
  927       second_pass.setFilterLimitsNegative (
true);
 
  928       second_pass.filter(nonground);
 
  948     nav_msgs::MapMetaData oldMapInfo = 
m_gridmap.info;
 
  951     double minX, minY, minZ, maxX, maxY, maxZ;
 
  960     ROS_DEBUG(
"MinKey: %d %d %d / MaxKey: %d %d %d", minKey[0], minKey[1], minKey[2], maxKey[0], maxKey[1], maxKey[2]);
 
  965     minX = std::min(minX, -halfPaddedX);
 
  967     minY = std::min(minY, -halfPaddedY);
 
  974       ROS_ERROR(
"Could not create padded min OcTree key at %f %f %f", minPt.
x(), minPt.
y(), minPt.
z());
 
  978       ROS_ERROR(
"Could not create padded max OcTree key at %f %f %f", maxPt.
x(), maxPt.
y(), maxPt.
z());
 
  983     assert(paddedMaxKey[0] >= maxKey[0] && paddedMaxKey[1] >= maxKey[1]);
 
  991     assert(mapOriginX >= 0 && mapOriginY >= 0);
 
  998     m_gridmap.info.origin.position.x = origin.
x() - gridRes*0.5;
 
  999     m_gridmap.info.origin.position.y = origin.
y() - gridRes*0.5;
 
 1012       ROS_DEBUG(
"Rebuilding complete 2D map");
 
 1023        nav_msgs::OccupancyGrid::_data_type::iterator startIt;
 
 1029        assert(mapUpdateBBXMaxX > mapUpdateBBXMinX);
 
 1030        assert(mapUpdateBBXMaxY > mapUpdateBBXMinY);
 
 1032        size_t numCols = mapUpdateBBXMaxX-mapUpdateBBXMinX +1;
 
 1035        uint max_idx = 
m_gridmap.info.width*mapUpdateBBXMaxY + mapUpdateBBXMaxX;
 
 1037          ROS_ERROR(
"BBX index not valid: %d (max index %zu for size %d x %d) update-BBX is: [%zu %zu]-[%zu %zu]", max_idx, 
m_gridmap.data.size(), 
m_gridmap.info.width, 
m_gridmap.info.height, mapUpdateBBXMinX, mapUpdateBBXMinY, mapUpdateBBXMaxX, mapUpdateBBXMaxY);
 
 1040        for (
unsigned int j = mapUpdateBBXMinY; j <= mapUpdateBBXMaxY; ++j){
 
 1085     unsigned idx = 
mapIdx(it.getKey());
 
 1095     for(
int dx=0; dx < intSize; dx++){
 
 1097       for(
int dy=0; dy < intSize; dy++){
 
 1115   bool neighborFound = 
false;
 
 1116   for (key[2] = nKey[2] - 1; !neighborFound && key[2] <= nKey[2] + 1; ++key[2]){
 
 1117     for (key[1] = nKey[1] - 1; !neighborFound && key[1] <= nKey[1] + 1; ++key[1]){
 
 1118       for (key[0] = nKey[0] - 1; !neighborFound && key[0] <= nKey[0] + 1; ++key[0]){
 
 1123             neighborFound = 
true;
 
 1130   return neighborFound;
 
 1182       if (
is_equal(config.sensor_model_hit, 1.0))
 
 1183                 config.sensor_model_hit -= 1.0e-6;
 
 1185           if (
is_equal(config.sensor_model_miss, 0.0))
 
 1186                 config.sensor_model_miss += 1.0e-6;
 
 1194   if (map.info.resolution != oldMapInfo.resolution){
 
 1195     ROS_ERROR(
"Resolution of map changed, cannot be adjusted");
 
 1199   int i_off = int((oldMapInfo.origin.position.x - map.info.origin.position.x)/map.info.resolution +0.5);
 
 1200   int j_off = int((oldMapInfo.origin.position.y - map.info.origin.position.y)/map.info.resolution +0.5);
 
 1202   if (i_off < 0 || j_off < 0
 
 1203       || oldMapInfo.width  + i_off > map.info.width
 
 1204       || oldMapInfo.height + j_off > map.info.height)
 
 1206     ROS_ERROR(
"New 2D map does not contain old map area, this case is not implemented");
 
 1210   nav_msgs::OccupancyGrid::_data_type oldMapData = map.data;
 
 1214   map.data.resize(map.info.width * map.info.height, -1);
 
 1216   nav_msgs::OccupancyGrid::_data_type::iterator fromStart, fromEnd, toStart;
 
 1218   for (
int j =0; j < int(oldMapInfo.height); ++j ){
 
 1220     fromStart = oldMapData.begin() + j*oldMapInfo.width;
 
 1221     fromEnd = fromStart + oldMapInfo.width;
 
 1222     toStart = map.data.begin() + ((j+j_off)*
m_gridmap.info.width + i_off);
 
 1223     copy(fromStart, fromEnd, toStart);
 
 1236   std_msgs::ColorRGBA color;
 
 1253   n = v * (1 - 
s * 
f);
 
 1258       color.r = v; color.g = n; color.b = m;
 
 1261       color.r = n; color.g = v; color.b = m;
 
 1264       color.r = m; color.g = v; color.b = n;
 
 1267       color.r = m; color.g = n; color.b = v;
 
 1270       color.r = n; color.g = m; color.b = v;
 
 1273       color.r = v; color.g = m; color.b = n;
 
 1276       color.r = 1; color.g = 0.5; color.b = 0.5;