OctomapServer.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010-2013, A. Hornung, University of Freiburg
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the University of Freiburg nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
31 
32 using namespace octomap;
33 using octomap_msgs::Octomap;
34 
35 bool is_equal (double a, double b, double epsilon = 1.0e-7)
36 {
37  return std::abs(a - b) < epsilon;
38 }
39 
40 namespace octomap_server{
41 
42 OctomapServer::OctomapServer(const ros::NodeHandle private_nh_, const ros::NodeHandle &nh_)
43 : m_nh(nh_),
44  m_nh_private(private_nh_),
45  m_pointCloudSub(NULL),
46  m_tfPointCloudSub(NULL),
47  m_reconfigureServer(m_config_mutex, private_nh_),
48  m_octree(NULL),
49  m_maxRange(-1.0),
50  m_worldFrameId("/map"), m_baseFrameId("base_footprint"),
51  m_useHeightMap(true),
52  m_useColoredMap(false),
53  m_colorFactor(0.8),
54  m_latchedTopics(true),
55  m_publishFreeSpace(false),
56  m_res(0.05),
57  m_treeDepth(0),
58  m_maxTreeDepth(0),
59  m_pointcloudMinX(-std::numeric_limits<double>::max()),
60  m_pointcloudMaxX(std::numeric_limits<double>::max()),
61  m_pointcloudMinY(-std::numeric_limits<double>::max()),
62  m_pointcloudMaxY(std::numeric_limits<double>::max()),
63  m_pointcloudMinZ(-std::numeric_limits<double>::max()),
64  m_pointcloudMaxZ(std::numeric_limits<double>::max()),
65  m_occupancyMinZ(-std::numeric_limits<double>::max()),
66  m_occupancyMaxZ(std::numeric_limits<double>::max()),
67  m_minSizeX(0.0), m_minSizeY(0.0),
68  m_filterSpeckles(false), m_filterGroundPlane(false),
69  m_groundFilterDistance(0.04), m_groundFilterAngle(0.15), m_groundFilterPlaneDistance(0.07),
70  m_compressMap(true),
71  m_incrementalUpdate(false),
72  m_initConfig(true)
73 {
74  double probHit, probMiss, thresMin, thresMax;
75 
77  m_nh_private.param("base_frame_id", m_baseFrameId, m_baseFrameId);
81 
90  m_nh_private.param("min_x_size", m_minSizeX,m_minSizeX);
91  m_nh_private.param("min_y_size", m_minSizeY,m_minSizeY);
92 
95  // distance of points from plane for RANSAC
97  // angular derivation of found plane:
99  // distance of found plane from z=0 to be detected as ground (e.g. to exclude tables)
101 
102  m_nh_private.param("sensor_model/max_range", m_maxRange, m_maxRange);
103 
104  m_nh_private.param("resolution", m_res, m_res);
105  m_nh_private.param("sensor_model/hit", probHit, 0.7);
106  m_nh_private.param("sensor_model/miss", probMiss, 0.4);
107  m_nh_private.param("sensor_model/min", thresMin, 0.12);
108  m_nh_private.param("sensor_model/max", thresMax, 0.97);
109  m_nh_private.param("compress_map", m_compressMap, m_compressMap);
110  m_nh_private.param("incremental_2D_projection", m_incrementalUpdate, m_incrementalUpdate);
111 
112  if (m_filterGroundPlane && (m_pointcloudMinZ > 0.0 || m_pointcloudMaxZ < 0.0)){
113  ROS_WARN_STREAM("You enabled ground filtering but incoming pointclouds will be pre-filtered in ["
114  <<m_pointcloudMinZ <<", "<< m_pointcloudMaxZ << "], excluding the ground level z=0. "
115  << "This will not work.");
116  }
117 
119  ROS_WARN_STREAM("You enabled both height map and RGB color registration. This is contradictory. Defaulting to height map.");
120  m_useColoredMap = false;
121  }
122 
123  if (m_useColoredMap) {
124 #ifdef COLOR_OCTOMAP_SERVER
125  ROS_INFO_STREAM("Using RGB color registration (if information available)");
126 #else
127  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");
128 #endif
129  }
130 
131  // initialize octomap object & params
132  m_octree = new OcTreeT(m_res);
133  m_octree->setProbHit(probHit);
134  m_octree->setProbMiss(probMiss);
135  m_octree->setClampingThresMin(thresMin);
136  m_octree->setClampingThresMax(thresMax);
139  m_gridmap.info.resolution = m_res;
140 
141  double r, g, b, a;
142  m_nh_private.param("color/r", r, 0.0);
143  m_nh_private.param("color/g", g, 0.0);
144  m_nh_private.param("color/b", b, 1.0);
145  m_nh_private.param("color/a", a, 1.0);
146  m_color.r = r;
147  m_color.g = g;
148  m_color.b = b;
149  m_color.a = a;
150 
151  m_nh_private.param("color_free/r", r, 0.0);
152  m_nh_private.param("color_free/g", g, 1.0);
153  m_nh_private.param("color_free/b", b, 0.0);
154  m_nh_private.param("color_free/a", a, 1.0);
155  m_colorFree.r = r;
156  m_colorFree.g = g;
157  m_colorFree.b = b;
158  m_colorFree.a = a;
159 
161 
163  if (m_latchedTopics){
164  ROS_INFO("Publishing latched (single publish will take longer, all topics are prepared)");
165  } else
166  ROS_INFO("Publishing non-latched (topics are only prepared as needed, will only be re-published on map change");
167 
168  m_markerPub = m_nh.advertise<visualization_msgs::MarkerArray>("occupied_cells_vis_array", 1, m_latchedTopics);
169  m_binaryMapPub = m_nh.advertise<Octomap>("octomap_binary", 1, m_latchedTopics);
170  m_fullMapPub = m_nh.advertise<Octomap>("octomap_full", 1, m_latchedTopics);
171  m_pointCloudPub = m_nh.advertise<sensor_msgs::PointCloud2>("octomap_point_cloud_centers", 1, m_latchedTopics);
172  m_mapPub = m_nh.advertise<nav_msgs::OccupancyGrid>("projected_map", 5, m_latchedTopics);
173  m_fmarkerPub = m_nh.advertise<visualization_msgs::MarkerArray>("free_cells_vis_array", 1, m_latchedTopics);
174 
177  m_tfPointCloudSub->registerCallback(boost::bind(&OctomapServer::insertCloudCallback, this, _1));
178 
179  m_octomapBinaryService = m_nh.advertiseService("octomap_binary", &OctomapServer::octomapBinarySrv, this);
180  m_octomapFullService = m_nh.advertiseService("octomap_full", &OctomapServer::octomapFullSrv, this);
183 
184  dynamic_reconfigure::Server<OctomapServerConfig>::CallbackType f;
185  f = boost::bind(&OctomapServer::reconfigureCallback, this, _1, _2);
186  m_reconfigureServer.setCallback(f);
187 }
188 
190  if (m_tfPointCloudSub){
191  delete m_tfPointCloudSub;
192  m_tfPointCloudSub = NULL;
193  }
194 
195  if (m_pointCloudSub){
196  delete m_pointCloudSub;
197  m_pointCloudSub = NULL;
198  }
199 
200 
201  if (m_octree){
202  delete m_octree;
203  m_octree = NULL;
204  }
205 
206 }
207 
208 bool OctomapServer::openFile(const std::string& filename){
209  if (filename.length() <= 3)
210  return false;
211 
212  std::string suffix = filename.substr(filename.length()-3, 3);
213  if (suffix== ".bt"){
214  if (!m_octree->readBinary(filename)){
215  return false;
216  }
217  } else if (suffix == ".ot"){
218  AbstractOcTree* tree = AbstractOcTree::read(filename);
219  if (!tree){
220  return false;
221  }
222  if (m_octree){
223  delete m_octree;
224  m_octree = NULL;
225  }
226  m_octree = dynamic_cast<OcTreeT*>(tree);
227  if (!m_octree){
228  ROS_ERROR("Could not read OcTree in file, currently there are no other types supported in .ot");
229  return false;
230  }
231 
232  } else{
233  return false;
234  }
235 
236  ROS_INFO("Octomap file %s loaded (%zu nodes).", filename.c_str(),m_octree->size());
237 
241  m_gridmap.info.resolution = m_res;
242  double minX, minY, minZ;
243  double maxX, maxY, maxZ;
244  m_octree->getMetricMin(minX, minY, minZ);
245  m_octree->getMetricMax(maxX, maxY, maxZ);
246 
247  m_updateBBXMin[0] = m_octree->coordToKey(minX);
248  m_updateBBXMin[1] = m_octree->coordToKey(minY);
249  m_updateBBXMin[2] = m_octree->coordToKey(minZ);
250 
251  m_updateBBXMax[0] = m_octree->coordToKey(maxX);
252  m_updateBBXMax[1] = m_octree->coordToKey(maxY);
253  m_updateBBXMax[2] = m_octree->coordToKey(maxZ);
254 
255  publishAll();
256 
257  return true;
258 
259 }
260 
261 void OctomapServer::insertCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& cloud){
262  ros::WallTime startTime = ros::WallTime::now();
263 
264 
265  //
266  // ground filtering in base frame
267  //
268  PCLPointCloud pc; // input cloud for filtering and ground-detection
269  pcl::fromROSMsg(*cloud, pc);
270 
271  tf::StampedTransform sensorToWorldTf;
272  try {
273  m_tfListener.lookupTransform(m_worldFrameId, cloud->header.frame_id, cloud->header.stamp, sensorToWorldTf);
274  } catch(tf::TransformException& ex){
275  ROS_ERROR_STREAM( "Transform error of sensor data: " << ex.what() << ", quitting callback");
276  return;
277  }
278 
279  Eigen::Matrix4f sensorToWorld;
280  pcl_ros::transformAsMatrix(sensorToWorldTf, sensorToWorld);
281 
282 
283  // set up filter for height range, also removes NANs:
284  pcl::PassThrough<PCLPoint> pass_x;
285  pass_x.setFilterFieldName("x");
286  pass_x.setFilterLimits(m_pointcloudMinX, m_pointcloudMaxX);
287  pcl::PassThrough<PCLPoint> pass_y;
288  pass_y.setFilterFieldName("y");
289  pass_y.setFilterLimits(m_pointcloudMinY, m_pointcloudMaxY);
290  pcl::PassThrough<PCLPoint> pass_z;
291  pass_z.setFilterFieldName("z");
292  pass_z.setFilterLimits(m_pointcloudMinZ, m_pointcloudMaxZ);
293 
294  PCLPointCloud pc_ground; // segmented ground plane
295  PCLPointCloud pc_nonground; // everything else
296 
297  if (m_filterGroundPlane){
298  tf::StampedTransform sensorToBaseTf, baseToWorldTf;
299  try{
300  m_tfListener.waitForTransform(m_baseFrameId, cloud->header.frame_id, cloud->header.stamp, ros::Duration(0.2));
301  m_tfListener.lookupTransform(m_baseFrameId, cloud->header.frame_id, cloud->header.stamp, sensorToBaseTf);
302  m_tfListener.lookupTransform(m_worldFrameId, m_baseFrameId, cloud->header.stamp, baseToWorldTf);
303 
304 
305  }catch(tf::TransformException& ex){
306  ROS_ERROR_STREAM( "Transform error for ground plane filter: " << ex.what() << ", quitting callback.\n"
307  "You need to set the base_frame_id or disable filter_ground.");
308  }
309 
310 
311  Eigen::Matrix4f sensorToBase, baseToWorld;
312  pcl_ros::transformAsMatrix(sensorToBaseTf, sensorToBase);
313  pcl_ros::transformAsMatrix(baseToWorldTf, baseToWorld);
314 
315  // transform pointcloud from sensor frame to fixed robot frame
316  pcl::transformPointCloud(pc, pc, sensorToBase);
317  pass_x.setInputCloud(pc.makeShared());
318  pass_x.filter(pc);
319  pass_y.setInputCloud(pc.makeShared());
320  pass_y.filter(pc);
321  pass_z.setInputCloud(pc.makeShared());
322  pass_z.filter(pc);
323  filterGroundPlane(pc, pc_ground, pc_nonground);
324 
325  // transform clouds to world frame for insertion
326  pcl::transformPointCloud(pc_ground, pc_ground, baseToWorld);
327  pcl::transformPointCloud(pc_nonground, pc_nonground, baseToWorld);
328  } else {
329  // directly transform to map frame:
330  pcl::transformPointCloud(pc, pc, sensorToWorld);
331 
332  // just filter height range:
333  pass_x.setInputCloud(pc.makeShared());
334  pass_x.filter(pc);
335  pass_y.setInputCloud(pc.makeShared());
336  pass_y.filter(pc);
337  pass_z.setInputCloud(pc.makeShared());
338  pass_z.filter(pc);
339 
340  pc_nonground = pc;
341  // pc_nonground is empty without ground segmentation
342  pc_ground.header = pc.header;
343  pc_nonground.header = pc.header;
344  }
345 
346 
347  insertScan(sensorToWorldTf.getOrigin(), pc_ground, pc_nonground);
348 
349  double total_elapsed = (ros::WallTime::now() - startTime).toSec();
350  ROS_DEBUG("Pointcloud insertion in OctomapServer done (%zu+%zu pts (ground/nonground), %f sec)", pc_ground.size(), pc_nonground.size(), total_elapsed);
351 
352  publishAll(cloud->header.stamp);
353 }
354 
355 void OctomapServer::insertScan(const tf::Point& sensorOriginTf, const PCLPointCloud& ground, const PCLPointCloud& nonground){
356  point3d sensorOrigin = pointTfToOctomap(sensorOriginTf);
357 
358  if (!m_octree->coordToKeyChecked(sensorOrigin, m_updateBBXMin)
359  || !m_octree->coordToKeyChecked(sensorOrigin, m_updateBBXMax))
360  {
361  ROS_ERROR_STREAM("Could not generate Key for origin "<<sensorOrigin);
362  }
363 
364 #ifdef COLOR_OCTOMAP_SERVER
365  unsigned char* colors = new unsigned char[3];
366 #endif
367 
368  // instead of direct scan insertion, compute update to filter ground:
369  KeySet free_cells, occupied_cells;
370  // insert ground points only as free:
371  for (PCLPointCloud::const_iterator it = ground.begin(); it != ground.end(); ++it){
372  point3d point(it->x, it->y, it->z);
373  // maxrange check
374  if ((m_maxRange > 0.0) && ((point - sensorOrigin).norm() > m_maxRange) ) {
375  point = sensorOrigin + (point - sensorOrigin).normalized() * m_maxRange;
376  }
377 
378  // only clear space (ground points)
379  if (m_octree->computeRayKeys(sensorOrigin, point, m_keyRay)){
380  free_cells.insert(m_keyRay.begin(), m_keyRay.end());
381  }
382 
383  octomap::OcTreeKey endKey;
384  if (m_octree->coordToKeyChecked(point, endKey)){
385  updateMinKey(endKey, m_updateBBXMin);
386  updateMaxKey(endKey, m_updateBBXMax);
387  } else{
388  ROS_ERROR_STREAM("Could not generate Key for endpoint "<<point);
389  }
390  }
391 
392  // all other points: free on ray, occupied on endpoint:
393  for (PCLPointCloud::const_iterator it = nonground.begin(); it != nonground.end(); ++it){
394  point3d point(it->x, it->y, it->z);
395  // maxrange check
396  if ((m_maxRange < 0.0) || ((point - sensorOrigin).norm() <= m_maxRange) ) {
397 
398  // free cells
399  if (m_octree->computeRayKeys(sensorOrigin, point, m_keyRay)){
400  free_cells.insert(m_keyRay.begin(), m_keyRay.end());
401  }
402  // occupied endpoint
403  OcTreeKey key;
404  if (m_octree->coordToKeyChecked(point, key)){
405  occupied_cells.insert(key);
406 
409 
410 #ifdef COLOR_OCTOMAP_SERVER // NB: Only read and interpret color if it's an occupied node
411  m_octree->averageNodeColor(it->x, it->y, it->z, /*r=*/it->r, /*g=*/it->g, /*b=*/it->b);
412 #endif
413  }
414  } else {// ray longer than maxrange:;
415  point3d new_end = sensorOrigin + (point - sensorOrigin).normalized() * m_maxRange;
416  if (m_octree->computeRayKeys(sensorOrigin, new_end, m_keyRay)){
417  free_cells.insert(m_keyRay.begin(), m_keyRay.end());
418 
419  octomap::OcTreeKey endKey;
420  if (m_octree->coordToKeyChecked(new_end, endKey)){
421  free_cells.insert(endKey);
422  updateMinKey(endKey, m_updateBBXMin);
423  updateMaxKey(endKey, m_updateBBXMax);
424  } else{
425  ROS_ERROR_STREAM("Could not generate Key for endpoint "<<new_end);
426  }
427 
428 
429  }
430  }
431  }
432 
433  // mark free cells only if not seen occupied in this cloud
434  for(KeySet::iterator it = free_cells.begin(), end=free_cells.end(); it!= end; ++it){
435  if (occupied_cells.find(*it) == occupied_cells.end()){
436  m_octree->updateNode(*it, false);
437  }
438  }
439 
440  // now mark all occupied cells:
441  for (KeySet::iterator it = occupied_cells.begin(), end=occupied_cells.end(); it!= end; it++) {
442  m_octree->updateNode(*it, true);
443  }
444 
445  // TODO: eval lazy+updateInner vs. proper insertion
446  // non-lazy by default (updateInnerOccupancy() too slow for large maps)
447  //m_octree->updateInnerOccupancy();
448  octomap::point3d minPt, maxPt;
449  ROS_DEBUG_STREAM("Bounding box keys (before): " << m_updateBBXMin[0] << " " <<m_updateBBXMin[1] << " " << m_updateBBXMin[2] << " / " <<m_updateBBXMax[0] << " "<<m_updateBBXMax[1] << " "<< m_updateBBXMax[2]);
450 
451  // TODO: snap max / min keys to larger voxels by m_maxTreeDepth
452 // if (m_maxTreeDepth < 16)
453 // {
454 // OcTreeKey tmpMin = getIndexKey(m_updateBBXMin, m_maxTreeDepth); // this should give us the first key at depth m_maxTreeDepth that is smaller or equal to m_updateBBXMin (i.e. lower left in 2D grid coordinates)
455 // OcTreeKey tmpMax = getIndexKey(m_updateBBXMax, m_maxTreeDepth); // see above, now add something to find upper right
456 // tmpMax[0]+= m_octree->getNodeSize( m_maxTreeDepth ) - 1;
457 // tmpMax[1]+= m_octree->getNodeSize( m_maxTreeDepth ) - 1;
458 // tmpMax[2]+= m_octree->getNodeSize( m_maxTreeDepth ) - 1;
459 // m_updateBBXMin = tmpMin;
460 // m_updateBBXMax = tmpMax;
461 // }
462 
463  // TODO: we could also limit the bbx to be within the map bounds here (see publishing check)
466  ROS_DEBUG_STREAM("Updated area bounding box: "<< minPt << " - "<<maxPt);
467  ROS_DEBUG_STREAM("Bounding box keys (after): " << m_updateBBXMin[0] << " " <<m_updateBBXMin[1] << " " << m_updateBBXMin[2] << " / " <<m_updateBBXMax[0] << " "<<m_updateBBXMax[1] << " "<< m_updateBBXMax[2]);
468 
469  if (m_compressMap)
470  m_octree->prune();
471 
472 #ifdef COLOR_OCTOMAP_SERVER
473  if (colors)
474  {
475  delete[] colors;
476  colors = NULL;
477  }
478 #endif
479 }
480 
481 
482 
484  ros::WallTime startTime = ros::WallTime::now();
485  size_t octomapSize = m_octree->size();
486  // TODO: estimate num occ. voxels for size of arrays (reserve)
487  if (octomapSize <= 1){
488  ROS_WARN("Nothing to publish, octree is empty");
489  return;
490  }
491 
492  bool publishFreeMarkerArray = m_publishFreeSpace && (m_latchedTopics || m_fmarkerPub.getNumSubscribers() > 0);
493  bool publishMarkerArray = (m_latchedTopics || m_markerPub.getNumSubscribers() > 0);
494  bool publishPointCloud = (m_latchedTopics || m_pointCloudPub.getNumSubscribers() > 0);
495  bool publishBinaryMap = (m_latchedTopics || m_binaryMapPub.getNumSubscribers() > 0);
496  bool publishFullMap = (m_latchedTopics || m_fullMapPub.getNumSubscribers() > 0);
498 
499  // init markers for free space:
500  visualization_msgs::MarkerArray freeNodesVis;
501  // each array stores all cubes of a different size, one for each depth level:
502  freeNodesVis.markers.resize(m_treeDepth+1);
503 
504  geometry_msgs::Pose pose;
505  pose.orientation = tf::createQuaternionMsgFromYaw(0.0);
506 
507  // init markers:
508  visualization_msgs::MarkerArray occupiedNodesVis;
509  // each array stores all cubes of a different size, one for each depth level:
510  occupiedNodesVis.markers.resize(m_treeDepth+1);
511 
512  // init pointcloud:
513  pcl::PointCloud<PCLPoint> pclCloud;
514 
515  // call pre-traversal hook:
516  handlePreNodeTraversal(rostime);
517 
518  // now, traverse all leafs in the tree:
520  end = m_octree->end(); it != end; ++it)
521  {
522  bool inUpdateBBX = isInUpdateBBX(it);
523 
524  // call general hook:
525  handleNode(it);
526  if (inUpdateBBX)
527  handleNodeInBBX(it);
528 
529  if (m_octree->isNodeOccupied(*it)){
530  double z = it.getZ();
531  double half_size = it.getSize() / 2.0;
532  if (z + half_size > m_occupancyMinZ && z - half_size < m_occupancyMaxZ)
533  {
534  double size = it.getSize();
535  double x = it.getX();
536  double y = it.getY();
537 #ifdef COLOR_OCTOMAP_SERVER
538  int r = it->getColor().r;
539  int g = it->getColor().g;
540  int b = it->getColor().b;
541 #endif
542 
543  // Ignore speckles in the map:
544  if (m_filterSpeckles && (it.getDepth() == m_treeDepth +1) && isSpeckleNode(it.getKey())){
545  ROS_DEBUG("Ignoring single speckle at (%f,%f,%f)", x, y, z);
546  continue;
547  } // else: current octree node is no speckle, send it out
548 
549  handleOccupiedNode(it);
550  if (inUpdateBBX)
552 
553 
554  //create marker:
555  if (publishMarkerArray){
556  unsigned idx = it.getDepth();
557  assert(idx < occupiedNodesVis.markers.size());
558 
559  geometry_msgs::Point cubeCenter;
560  cubeCenter.x = x;
561  cubeCenter.y = y;
562  cubeCenter.z = z;
563 
564  occupiedNodesVis.markers[idx].points.push_back(cubeCenter);
565  if (m_useHeightMap){
566  double minX, minY, minZ, maxX, maxY, maxZ;
567  m_octree->getMetricMin(minX, minY, minZ);
568  m_octree->getMetricMax(maxX, maxY, maxZ);
569 
570  double h = (1.0 - std::min(std::max((cubeCenter.z-minZ)/ (maxZ - minZ), 0.0), 1.0)) *m_colorFactor;
571  occupiedNodesVis.markers[idx].colors.push_back(heightMapColor(h));
572  }
573 
574 #ifdef COLOR_OCTOMAP_SERVER
575  if (m_useColoredMap) {
576  std_msgs::ColorRGBA _color; _color.r = (r / 255.); _color.g = (g / 255.); _color.b = (b / 255.); _color.a = 1.0; // TODO/EVALUATE: potentially use occupancy as measure for alpha channel?
577  occupiedNodesVis.markers[idx].colors.push_back(_color);
578  }
579 #endif
580  }
581 
582  // insert into pointcloud:
583  if (publishPointCloud) {
584 #ifdef COLOR_OCTOMAP_SERVER
585  PCLPoint _point = PCLPoint();
586  _point.x = x; _point.y = y; _point.z = z;
587  _point.r = r; _point.g = g; _point.b = b;
588  pclCloud.push_back(_point);
589 #else
590  pclCloud.push_back(PCLPoint(x, y, z));
591 #endif
592  }
593 
594  }
595  } else{ // node not occupied => mark as free in 2D map if unknown so far
596  double z = it.getZ();
597  double half_size = it.getSize() / 2.0;
598  if (z + half_size > m_occupancyMinZ && z - half_size < m_occupancyMaxZ)
599  {
600  handleFreeNode(it);
601  if (inUpdateBBX)
603 
604  if (m_publishFreeSpace){
605  double x = it.getX();
606  double y = it.getY();
607 
608  //create marker for free space:
609  if (publishFreeMarkerArray){
610  unsigned idx = it.getDepth();
611  assert(idx < freeNodesVis.markers.size());
612 
613  geometry_msgs::Point cubeCenter;
614  cubeCenter.x = x;
615  cubeCenter.y = y;
616  cubeCenter.z = z;
617 
618  freeNodesVis.markers[idx].points.push_back(cubeCenter);
619  }
620  }
621 
622  }
623  }
624  }
625 
626  // call post-traversal hook:
627  handlePostNodeTraversal(rostime);
628 
629  // finish MarkerArray:
630  if (publishMarkerArray){
631  for (unsigned i= 0; i < occupiedNodesVis.markers.size(); ++i){
632  double size = m_octree->getNodeSize(i);
633 
634  occupiedNodesVis.markers[i].header.frame_id = m_worldFrameId;
635  occupiedNodesVis.markers[i].header.stamp = rostime;
636  occupiedNodesVis.markers[i].ns = "map";
637  occupiedNodesVis.markers[i].id = i;
638  occupiedNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
639  occupiedNodesVis.markers[i].scale.x = size;
640  occupiedNodesVis.markers[i].scale.y = size;
641  occupiedNodesVis.markers[i].scale.z = size;
642  if (!m_useColoredMap)
643  occupiedNodesVis.markers[i].color = m_color;
644 
645 
646  if (occupiedNodesVis.markers[i].points.size() > 0)
647  occupiedNodesVis.markers[i].action = visualization_msgs::Marker::ADD;
648  else
649  occupiedNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
650  }
651 
652  m_markerPub.publish(occupiedNodesVis);
653  }
654 
655 
656  // finish FreeMarkerArray:
657  if (publishFreeMarkerArray){
658  for (unsigned i= 0; i < freeNodesVis.markers.size(); ++i){
659  double size = m_octree->getNodeSize(i);
660 
661  freeNodesVis.markers[i].header.frame_id = m_worldFrameId;
662  freeNodesVis.markers[i].header.stamp = rostime;
663  freeNodesVis.markers[i].ns = "map";
664  freeNodesVis.markers[i].id = i;
665  freeNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
666  freeNodesVis.markers[i].scale.x = size;
667  freeNodesVis.markers[i].scale.y = size;
668  freeNodesVis.markers[i].scale.z = size;
669  freeNodesVis.markers[i].color = m_colorFree;
670 
671 
672  if (freeNodesVis.markers[i].points.size() > 0)
673  freeNodesVis.markers[i].action = visualization_msgs::Marker::ADD;
674  else
675  freeNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
676  }
677 
678  m_fmarkerPub.publish(freeNodesVis);
679  }
680 
681 
682  // finish pointcloud:
683  if (publishPointCloud){
684  sensor_msgs::PointCloud2 cloud;
685  pcl::toROSMsg (pclCloud, cloud);
686  cloud.header.frame_id = m_worldFrameId;
687  cloud.header.stamp = rostime;
688  m_pointCloudPub.publish(cloud);
689  }
690 
691  if (publishBinaryMap)
692  publishBinaryOctoMap(rostime);
693 
694  if (publishFullMap)
695  publishFullOctoMap(rostime);
696 
697 
698  double total_elapsed = (ros::WallTime::now() - startTime).toSec();
699  ROS_DEBUG("Map publishing in OctomapServer took %f sec", total_elapsed);
700 
701 }
702 
703 
704 bool OctomapServer::octomapBinarySrv(OctomapSrv::Request &req,
705  OctomapSrv::Response &res)
706 {
707  ros::WallTime startTime = ros::WallTime::now();
708  ROS_INFO("Sending binary map data on service request");
709  res.map.header.frame_id = m_worldFrameId;
710  res.map.header.stamp = ros::Time::now();
711  if (!octomap_msgs::binaryMapToMsg(*m_octree, res.map))
712  return false;
713 
714  double total_elapsed = (ros::WallTime::now() - startTime).toSec();
715  ROS_INFO("Binary octomap sent in %f sec", total_elapsed);
716  return true;
717 }
718 
719 bool OctomapServer::octomapFullSrv(OctomapSrv::Request &req,
720  OctomapSrv::Response &res)
721 {
722  ROS_INFO("Sending full map data on service request");
723  res.map.header.frame_id = m_worldFrameId;
724  res.map.header.stamp = ros::Time::now();
725 
726 
727  if (!octomap_msgs::fullMapToMsg(*m_octree, res.map))
728  return false;
729 
730  return true;
731 }
732 
733 bool OctomapServer::clearBBXSrv(BBXSrv::Request& req, BBXSrv::Response& resp){
734  point3d min = pointMsgToOctomap(req.min);
735  point3d max = pointMsgToOctomap(req.max);
736 
737  double thresMin = m_octree->getClampingThresMin();
738  for(OcTreeT::leaf_bbx_iterator it = m_octree->begin_leafs_bbx(min,max),
739  end=m_octree->end_leafs_bbx(); it!= end; ++it){
740 
741  it->setLogOdds(octomap::logodds(thresMin));
742  // m_octree->updateNode(it.getKey(), -6.0f);
743  }
744  // TODO: eval which is faster (setLogOdds+updateInner or updateNode)
746 
748 
749  return true;
750 }
751 
752 bool OctomapServer::resetSrv(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp) {
753  visualization_msgs::MarkerArray occupiedNodesVis;
754  occupiedNodesVis.markers.resize(m_treeDepth +1);
755  ros::Time rostime = ros::Time::now();
756  m_octree->clear();
757  // clear 2D map:
758  m_gridmap.data.clear();
759  m_gridmap.info.height = 0.0;
760  m_gridmap.info.width = 0.0;
761  m_gridmap.info.resolution = 0.0;
762  m_gridmap.info.origin.position.x = 0.0;
763  m_gridmap.info.origin.position.y = 0.0;
764 
765  ROS_INFO("Cleared octomap");
766  publishAll(rostime);
767 
768  publishBinaryOctoMap(rostime);
769  for (unsigned i= 0; i < occupiedNodesVis.markers.size(); ++i){
770 
771  occupiedNodesVis.markers[i].header.frame_id = m_worldFrameId;
772  occupiedNodesVis.markers[i].header.stamp = rostime;
773  occupiedNodesVis.markers[i].ns = "map";
774  occupiedNodesVis.markers[i].id = i;
775  occupiedNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
776  occupiedNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
777  }
778 
779  m_markerPub.publish(occupiedNodesVis);
780 
781  visualization_msgs::MarkerArray freeNodesVis;
782  freeNodesVis.markers.resize(m_treeDepth +1);
783 
784  for (unsigned i= 0; i < freeNodesVis.markers.size(); ++i){
785 
786  freeNodesVis.markers[i].header.frame_id = m_worldFrameId;
787  freeNodesVis.markers[i].header.stamp = rostime;
788  freeNodesVis.markers[i].ns = "map";
789  freeNodesVis.markers[i].id = i;
790  freeNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
791  freeNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
792  }
793  m_fmarkerPub.publish(freeNodesVis);
794 
795  return true;
796 }
797 
799 
800  Octomap map;
801  map.header.frame_id = m_worldFrameId;
802  map.header.stamp = rostime;
803 
805  m_binaryMapPub.publish(map);
806  else
807  ROS_ERROR("Error serializing OctoMap");
808 }
809 
810 void OctomapServer::publishFullOctoMap(const ros::Time& rostime) const{
811 
812  Octomap map;
813  map.header.frame_id = m_worldFrameId;
814  map.header.stamp = rostime;
815 
817  m_fullMapPub.publish(map);
818  else
819  ROS_ERROR("Error serializing OctoMap");
820 
821 }
822 
823 
825  ground.header = pc.header;
826  nonground.header = pc.header;
827 
828  if (pc.size() < 50){
829  ROS_WARN("Pointcloud in OctomapServer too small, skipping ground plane extraction");
830  nonground = pc;
831  } else {
832  // plane detection for ground plane removal:
833  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
834  pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
835 
836  // Create the segmentation object and set up:
837  pcl::SACSegmentation<PCLPoint> seg;
838  seg.setOptimizeCoefficients (true);
839  // TODO: maybe a filtering based on the surface normals might be more robust / accurate?
840  seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
841  seg.setMethodType(pcl::SAC_RANSAC);
842  seg.setMaxIterations(200);
843  seg.setDistanceThreshold (m_groundFilterDistance);
844  seg.setAxis(Eigen::Vector3f(0,0,1));
845  seg.setEpsAngle(m_groundFilterAngle);
846 
847 
848  PCLPointCloud cloud_filtered(pc);
849  // Create the filtering object
850  pcl::ExtractIndices<PCLPoint> extract;
851  bool groundPlaneFound = false;
852 
853  while(cloud_filtered.size() > 10 && !groundPlaneFound){
854  seg.setInputCloud(cloud_filtered.makeShared());
855  seg.segment (*inliers, *coefficients);
856  if (inliers->indices.size () == 0){
857  ROS_INFO("PCL segmentation did not find any plane.");
858 
859  break;
860  }
861 
862  extract.setInputCloud(cloud_filtered.makeShared());
863  extract.setIndices(inliers);
864 
865  if (std::abs(coefficients->values.at(3)) < m_groundFilterPlaneDistance){
866  ROS_DEBUG("Ground plane found: %zu/%zu inliers. Coeff: %f %f %f %f", inliers->indices.size(), cloud_filtered.size(),
867  coefficients->values.at(0), coefficients->values.at(1), coefficients->values.at(2), coefficients->values.at(3));
868  extract.setNegative (false);
869  extract.filter (ground);
870 
871  // remove ground points from full pointcloud:
872  // workaround for PCL bug:
873  if(inliers->indices.size() != cloud_filtered.size()){
874  extract.setNegative(true);
875  PCLPointCloud cloud_out;
876  extract.filter(cloud_out);
877  nonground += cloud_out;
878  cloud_filtered = cloud_out;
879  }
880 
881  groundPlaneFound = true;
882  } else{
883  ROS_DEBUG("Horizontal plane (not ground) found: %zu/%zu inliers. Coeff: %f %f %f %f", inliers->indices.size(), cloud_filtered.size(),
884  coefficients->values.at(0), coefficients->values.at(1), coefficients->values.at(2), coefficients->values.at(3));
885  pcl::PointCloud<PCLPoint> cloud_out;
886  extract.setNegative (false);
887  extract.filter(cloud_out);
888  nonground +=cloud_out;
889  // debug
890  // pcl::PCDWriter writer;
891  // writer.write<PCLPoint>("nonground_plane.pcd",cloud_out, false);
892 
893  // remove current plane from scan for next iteration:
894  // workaround for PCL bug:
895  if(inliers->indices.size() != cloud_filtered.size()){
896  extract.setNegative(true);
897  cloud_out.points.clear();
898  extract.filter(cloud_out);
899  cloud_filtered = cloud_out;
900  } else{
901  cloud_filtered.points.clear();
902  }
903  }
904 
905  }
906  // TODO: also do this if overall starting pointcloud too small?
907  if (!groundPlaneFound){ // no plane found or remaining points too small
908  ROS_WARN("No ground plane found in scan");
909 
910  // do a rough fitlering on height to prevent spurious obstacles
911  pcl::PassThrough<PCLPoint> second_pass;
912  second_pass.setFilterFieldName("z");
913  second_pass.setFilterLimits(-m_groundFilterPlaneDistance, m_groundFilterPlaneDistance);
914  second_pass.setInputCloud(pc.makeShared());
915  second_pass.filter(ground);
916 
917  second_pass.setFilterLimitsNegative (true);
918  second_pass.filter(nonground);
919  }
920 
921  // debug:
922  // pcl::PCDWriter writer;
923  // if (pc_ground.size() > 0)
924  // writer.write<PCLPoint>("ground.pcd",pc_ground, false);
925  // if (pc_nonground.size() > 0)
926  // writer.write<PCLPoint>("nonground.pcd",pc_nonground, false);
927 
928  }
929 
930 
931 }
932 
934  if (m_publish2DMap){
935  // init projected 2D map:
936  m_gridmap.header.frame_id = m_worldFrameId;
937  m_gridmap.header.stamp = rostime;
938  nav_msgs::MapMetaData oldMapInfo = m_gridmap.info;
939 
940  // TODO: move most of this stuff into c'tor and init map only once (adjust if size changes)
941  double minX, minY, minZ, maxX, maxY, maxZ;
942  m_octree->getMetricMin(minX, minY, minZ);
943  m_octree->getMetricMax(maxX, maxY, maxZ);
944 
945  octomap::point3d minPt(minX, minY, minZ);
946  octomap::point3d maxPt(maxX, maxY, maxZ);
949 
950  ROS_DEBUG("MinKey: %d %d %d / MaxKey: %d %d %d", minKey[0], minKey[1], minKey[2], maxKey[0], maxKey[1], maxKey[2]);
951 
952  // add padding if requested (= new min/maxPts in x&y):
953  double halfPaddedX = 0.5*m_minSizeX;
954  double halfPaddedY = 0.5*m_minSizeY;
955  minX = std::min(minX, -halfPaddedX);
956  maxX = std::max(maxX, halfPaddedX);
957  minY = std::min(minY, -halfPaddedY);
958  maxY = std::max(maxY, halfPaddedY);
959  minPt = octomap::point3d(minX, minY, minZ);
960  maxPt = octomap::point3d(maxX, maxY, maxZ);
961 
962  OcTreeKey paddedMaxKey;
964  ROS_ERROR("Could not create padded min OcTree key at %f %f %f", minPt.x(), minPt.y(), minPt.z());
965  return;
966  }
967  if (!m_octree->coordToKeyChecked(maxPt, m_maxTreeDepth, paddedMaxKey)){
968  ROS_ERROR("Could not create padded max OcTree key at %f %f %f", maxPt.x(), maxPt.y(), maxPt.z());
969  return;
970  }
971 
972  ROS_DEBUG("Padded MinKey: %d %d %d / padded MaxKey: %d %d %d", m_paddedMinKey[0], m_paddedMinKey[1], m_paddedMinKey[2], paddedMaxKey[0], paddedMaxKey[1], paddedMaxKey[2]);
973  assert(paddedMaxKey[0] >= maxKey[0] && paddedMaxKey[1] >= maxKey[1]);
974 
976  m_gridmap.info.width = (paddedMaxKey[0] - m_paddedMinKey[0])/m_multires2DScale +1;
977  m_gridmap.info.height = (paddedMaxKey[1] - m_paddedMinKey[1])/m_multires2DScale +1;
978 
979  int mapOriginX = minKey[0] - m_paddedMinKey[0];
980  int mapOriginY = minKey[1] - m_paddedMinKey[1];
981  assert(mapOriginX >= 0 && mapOriginY >= 0);
982 
983  // might not exactly be min / max of octree:
984  octomap::point3d origin = m_octree->keyToCoord(m_paddedMinKey, m_treeDepth);
985  double gridRes = m_octree->getNodeSize(m_maxTreeDepth);
986  m_projectCompleteMap = (!m_incrementalUpdate || (std::abs(gridRes-m_gridmap.info.resolution) > 1e-6));
987  m_gridmap.info.resolution = gridRes;
988  m_gridmap.info.origin.position.x = origin.x() - gridRes*0.5;
989  m_gridmap.info.origin.position.y = origin.y() - gridRes*0.5;
990  if (m_maxTreeDepth != m_treeDepth){
991  m_gridmap.info.origin.position.x -= m_res/2.0;
992  m_gridmap.info.origin.position.y -= m_res/2.0;
993  }
994 
995  // workaround for multires. projection not working properly for inner nodes:
996  // force re-building complete map
998  m_projectCompleteMap = true;
999 
1000 
1002  ROS_DEBUG("Rebuilding complete 2D map");
1003  m_gridmap.data.clear();
1004  // init to unknown:
1005  m_gridmap.data.resize(m_gridmap.info.width * m_gridmap.info.height, -1);
1006 
1007  } else {
1008 
1009  if (mapChanged(oldMapInfo, m_gridmap.info)){
1010  ROS_DEBUG("2D grid map size changed to %dx%d", m_gridmap.info.width, m_gridmap.info.height);
1011  adjustMapData(m_gridmap, oldMapInfo);
1012  }
1013  nav_msgs::OccupancyGrid::_data_type::iterator startIt;
1014  size_t mapUpdateBBXMinX = std::max(0, (int(m_updateBBXMin[0]) - int(m_paddedMinKey[0]))/int(m_multires2DScale));
1015  size_t mapUpdateBBXMinY = std::max(0, (int(m_updateBBXMin[1]) - int(m_paddedMinKey[1]))/int(m_multires2DScale));
1016  size_t mapUpdateBBXMaxX = std::min(int(m_gridmap.info.width-1), (int(m_updateBBXMax[0]) - int(m_paddedMinKey[0]))/int(m_multires2DScale));
1017  size_t mapUpdateBBXMaxY = std::min(int(m_gridmap.info.height-1), (int(m_updateBBXMax[1]) - int(m_paddedMinKey[1]))/int(m_multires2DScale));
1018 
1019  assert(mapUpdateBBXMaxX > mapUpdateBBXMinX);
1020  assert(mapUpdateBBXMaxY > mapUpdateBBXMinY);
1021 
1022  size_t numCols = mapUpdateBBXMaxX-mapUpdateBBXMinX +1;
1023 
1024  // test for max idx:
1025  uint max_idx = m_gridmap.info.width*mapUpdateBBXMaxY + mapUpdateBBXMaxX;
1026  if (max_idx >= m_gridmap.data.size())
1027  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);
1028 
1029  // reset proj. 2D map in bounding box:
1030  for (unsigned int j = mapUpdateBBXMinY; j <= mapUpdateBBXMaxY; ++j){
1031  std::fill_n(m_gridmap.data.begin() + m_gridmap.info.width*j+mapUpdateBBXMinX,
1032  numCols, -1);
1033  }
1034 
1035  }
1036 
1037 
1038 
1039  }
1040 
1041 }
1042 
1044 
1045  if (m_publish2DMap)
1047 }
1048 
1050 
1052  update2DMap(it, true);
1053  }
1054 }
1055 
1057 
1059  update2DMap(it, false);
1060  }
1061 }
1062 
1064 
1066  update2DMap(it, true);
1067  }
1068 }
1069 
1071 
1073  update2DMap(it, false);
1074  }
1075 }
1076 
1077 void OctomapServer::update2DMap(const OcTreeT::iterator& it, bool occupied){
1078 
1079  // update 2D map (occupied always overrides):
1080 
1081  if (it.getDepth() == m_maxTreeDepth){
1082  unsigned idx = mapIdx(it.getKey());
1083  if (occupied)
1084  m_gridmap.data[mapIdx(it.getKey())] = 100;
1085  else if (m_gridmap.data[idx] == -1){
1086  m_gridmap.data[idx] = 0;
1087  }
1088 
1089  } else{
1090  int intSize = 1 << (m_maxTreeDepth - it.getDepth());
1091  octomap::OcTreeKey minKey=it.getIndexKey();
1092  for(int dx=0; dx < intSize; dx++){
1093  int i = (minKey[0]+dx - m_paddedMinKey[0])/m_multires2DScale;
1094  for(int dy=0; dy < intSize; dy++){
1095  unsigned idx = mapIdx(i, (minKey[1]+dy - m_paddedMinKey[1])/m_multires2DScale);
1096  if (occupied)
1097  m_gridmap.data[idx] = 100;
1098  else if (m_gridmap.data[idx] == -1){
1099  m_gridmap.data[idx] = 0;
1100  }
1101  }
1102  }
1103  }
1104 
1105 
1106 }
1107 
1108 
1109 
1110 bool OctomapServer::isSpeckleNode(const OcTreeKey&nKey) const {
1111  OcTreeKey key;
1112  bool neighborFound = false;
1113  for (key[2] = nKey[2] - 1; !neighborFound && key[2] <= nKey[2] + 1; ++key[2]){
1114  for (key[1] = nKey[1] - 1; !neighborFound && key[1] <= nKey[1] + 1; ++key[1]){
1115  for (key[0] = nKey[0] - 1; !neighborFound && key[0] <= nKey[0] + 1; ++key[0]){
1116  if (key != nKey){
1117  OcTreeNode* node = m_octree->search(key);
1118  if (node && m_octree->isNodeOccupied(node)){
1119  // we have a neighbor => break!
1120  neighborFound = true;
1121  }
1122  }
1123  }
1124  }
1125  }
1126 
1127  return neighborFound;
1128 }
1129 
1130 void OctomapServer::reconfigureCallback(octomap_server::OctomapServerConfig& config, uint32_t level){
1131  if (m_maxTreeDepth != unsigned(config.max_depth))
1132  m_maxTreeDepth = unsigned(config.max_depth);
1133  else{
1134  m_pointcloudMinZ = config.pointcloud_min_z;
1135  m_pointcloudMaxZ = config.pointcloud_max_z;
1136  m_occupancyMinZ = config.occupancy_min_z;
1137  m_occupancyMaxZ = config.occupancy_max_z;
1138  m_filterSpeckles = config.filter_speckles;
1139  m_filterGroundPlane = config.filter_ground;
1140  m_compressMap = config.compress_map;
1141  m_incrementalUpdate = config.incremental_2D_projection;
1142 
1143  // Parameters with a namespace require an special treatment at the beginning, as dynamic reconfigure
1144  // will overwrite them because the server is not able to match parameters' names.
1145  if (m_initConfig){
1146  // If parameters do not have the default value, dynamic reconfigure server should be updated.
1147  if(!is_equal(m_groundFilterDistance, 0.04))
1148  config.ground_filter_distance = m_groundFilterDistance;
1149  if(!is_equal(m_groundFilterAngle, 0.15))
1150  config.ground_filter_angle = m_groundFilterAngle;
1152  config.ground_filter_plane_distance = m_groundFilterPlaneDistance;
1153  if(!is_equal(m_maxRange, -1.0))
1154  config.sensor_model_max_range = m_maxRange;
1155  if(!is_equal(m_octree->getProbHit(), 0.7))
1156  config.sensor_model_hit = m_octree->getProbHit();
1157  if(!is_equal(m_octree->getProbMiss(), 0.4))
1158  config.sensor_model_miss = m_octree->getProbMiss();
1159  if(!is_equal(m_octree->getClampingThresMin(), 0.12))
1160  config.sensor_model_min = m_octree->getClampingThresMin();
1161  if(!is_equal(m_octree->getClampingThresMax(), 0.97))
1162  config.sensor_model_max = m_octree->getClampingThresMax();
1163  m_initConfig = false;
1164 
1165  boost::recursive_mutex::scoped_lock reconf_lock(m_config_mutex);
1166  m_reconfigureServer.updateConfig(config);
1167  }
1168  else{
1169  m_groundFilterDistance = config.ground_filter_distance;
1170  m_groundFilterAngle = config.ground_filter_angle;
1171  m_groundFilterPlaneDistance = config.ground_filter_plane_distance;
1172  m_maxRange = config.sensor_model_max_range;
1173  m_octree->setClampingThresMin(config.sensor_model_min);
1174  m_octree->setClampingThresMax(config.sensor_model_max);
1175 
1176  // Checking values that might create unexpected behaviors.
1177  if (is_equal(config.sensor_model_hit, 1.0))
1178  config.sensor_model_hit -= 1.0e-6;
1179  m_octree->setProbHit(config.sensor_model_hit);
1180  if (is_equal(config.sensor_model_miss, 0.0))
1181  config.sensor_model_miss += 1.0e-6;
1182  m_octree->setProbMiss(config.sensor_model_miss);
1183  }
1184  }
1185  publishAll();
1186 }
1187 
1188 void OctomapServer::adjustMapData(nav_msgs::OccupancyGrid& map, const nav_msgs::MapMetaData& oldMapInfo) const{
1189  if (map.info.resolution != oldMapInfo.resolution){
1190  ROS_ERROR("Resolution of map changed, cannot be adjusted");
1191  return;
1192  }
1193 
1194  int i_off = int((oldMapInfo.origin.position.x - map.info.origin.position.x)/map.info.resolution +0.5);
1195  int j_off = int((oldMapInfo.origin.position.y - map.info.origin.position.y)/map.info.resolution +0.5);
1196 
1197  if (i_off < 0 || j_off < 0
1198  || oldMapInfo.width + i_off > map.info.width
1199  || oldMapInfo.height + j_off > map.info.height)
1200  {
1201  ROS_ERROR("New 2D map does not contain old map area, this case is not implemented");
1202  return;
1203  }
1204 
1205  nav_msgs::OccupancyGrid::_data_type oldMapData = map.data;
1206 
1207  map.data.clear();
1208  // init to unknown:
1209  map.data.resize(map.info.width * map.info.height, -1);
1210 
1211  nav_msgs::OccupancyGrid::_data_type::iterator fromStart, fromEnd, toStart;
1212 
1213  for (int j =0; j < int(oldMapInfo.height); ++j ){
1214  // copy chunks, row by row:
1215  fromStart = oldMapData.begin() + j*oldMapInfo.width;
1216  fromEnd = fromStart + oldMapInfo.width;
1217  toStart = map.data.begin() + ((j+j_off)*m_gridmap.info.width + i_off);
1218  copy(fromStart, fromEnd, toStart);
1219 
1220 // for (int i =0; i < int(oldMapInfo.width); ++i){
1221 // map.data[m_gridmap.info.width*(j+j_off) +i+i_off] = oldMapData[oldMapInfo.width*j +i];
1222 // }
1223 
1224  }
1225 
1226 }
1227 
1228 
1229 std_msgs::ColorRGBA OctomapServer::heightMapColor(double h) {
1230 
1231  std_msgs::ColorRGBA color;
1232  color.a = 1.0;
1233  // blend over HSV-values (more colors)
1234 
1235  double s = 1.0;
1236  double v = 1.0;
1237 
1238  h -= floor(h);
1239  h *= 6;
1240  int i;
1241  double m, n, f;
1242 
1243  i = floor(h);
1244  f = h - i;
1245  if (!(i & 1))
1246  f = 1 - f; // if i is even
1247  m = v * (1 - s);
1248  n = v * (1 - s * f);
1249 
1250  switch (i) {
1251  case 6:
1252  case 0:
1253  color.r = v; color.g = n; color.b = m;
1254  break;
1255  case 1:
1256  color.r = n; color.g = v; color.b = m;
1257  break;
1258  case 2:
1259  color.r = m; color.g = v; color.b = n;
1260  break;
1261  case 3:
1262  color.r = m; color.g = n; color.b = v;
1263  break;
1264  case 4:
1265  color.r = n; color.g = m; color.b = v;
1266  break;
1267  case 5:
1268  color.r = v; color.g = m; color.b = n;
1269  break;
1270  default:
1271  color.r = 1; color.g = 0.5; color.b = 0.5;
1272  break;
1273  }
1274 
1275  return color;
1276 }
1277 }
1278 
1279 
1280 
tf::TransformListener m_tfListener
iterator begin()
virtual bool octomapBinarySrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res)
double epsilon
iterator begin(unsigned char maxDepth=0) const
virtual void insertCloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud)
void publish(const boost::shared_ptr< M > &message) const
virtual bool octomapFullSrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res)
octomap::OcTreeKey m_updateBBXMax
unsigned short int coordToKey(double coordinate) const
f
static void updateMaxKey(const octomap::OcTreeKey &in, octomap::OcTreeKey &max)
octomap::OcTreeKey m_updateBBXMin
void setClampingThresMax(double thresProb)
virtual OcTreeNode * updateNode(const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)
bool is_equal(double a, double b, double epsilon=1.0e-7)
XmlRpcServer s
static bool fullMapToMsg(const OctomapT &octomap, Octomap &msg)
void transformAsMatrix(const tf::Transform &bt, Eigen::Matrix4f &out_mat)
virtual void handleFreeNodeInBBX(const OcTreeT::iterator &it)
hook that is called when traversing free nodes in the updated area (updates 2D map projection here) ...
bool mapChanged(const nav_msgs::MapMetaData &oldMapInfo, const nav_msgs::MapMetaData &newMapInfo)
leaf_bbx_iterator begin_leafs_bbx(const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth=0) const
OcTreeNode * search(double x, double y, double z, unsigned int depth=0) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
void publishBinaryOctoMap(const ros::Time &rostime=ros::Time::now()) const
bool isInUpdateBBX(const OcTreeT::iterator &it) const
Test if key is within update area of map (2D, ignores height)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool coordToKeyChecked(const point3d &coord, OcTreeKey &key) const
bool resetSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void reconfigureCallback(octomap_server::OctomapServerConfig &config, uint32_t level)
#define ROS_WARN(...)
bool clearBBXSrv(BBXSrv::Request &req, BBXSrv::Response &resp)
static bool binaryMapToMsg(const OctomapT &octomap, Octomap &msg)
ros::ServiceServer m_octomapBinaryService
double keyToCoord(unsigned short int key, unsigned depth) const
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
static void updateMinKey(const octomap::OcTreeKey &in, octomap::OcTreeKey &min)
bool computeRayKeys(const point3d &origin, const point3d &end, KeyRay &ray) const
TFSIMD_FORCE_INLINE Vector3 normalized() const
static std_msgs::ColorRGBA heightMapColor(double h)
virtual void handlePreNodeTraversal(const ros::Time &rostime)
hook that is called before traversing all nodes
octomap::OcTreeKey m_paddedMinKey
virtual void handleOccupiedNode(const OcTreeT::iterator &it)
hook that is called when traversing occupied nodes of the updated Octree
bool isSpeckleNode(const octomap::OcTreeKey &key) const
Find speckle nodes (single occupied voxels with no neighbors). Only works on lowest resolution! ...
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std_msgs::ColorRGBA m_color
virtual void getMetricMin(double &x, double &y, double &z)
virtual void insertScan(const tf::Point &sensorOrigin, const PCLPointCloud &ground, const PCLPointCloud &nonground)
update occupancy map with a scan labeled as ground and nonground. The scans should be in the global m...
void adjustMapData(nav_msgs::OccupancyGrid &map, const nav_msgs::MapMetaData &oldMapInfo) const
unordered_ns::unordered_set< OcTreeKey, OcTreeKey::KeyHash > KeySet
TFSIMD_FORCE_INLINE const tfScalar & x() const
void publishFullOctoMap(const ros::Time &rostime=ros::Time::now()) const
std_msgs::ColorRGBA m_colorFree
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
TFSIMD_FORCE_INLINE const tfScalar & z() const
iterator end()
virtual void getMetricMax(double &x, double &y, double &z)
tf::MessageFilter< sensor_msgs::PointCloud2 > * m_tfPointCloudSub
dynamic_reconfigure::Server< OctomapServerConfig > m_reconfigureServer
message_filters::Subscriber< sensor_msgs::PointCloud2 > * m_pointCloudSub
ros::ServiceServer m_octomapFullService
uint32_t getNumSubscribers() const
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
#define ROS_INFO_STREAM(args)
static WallTime now()
virtual void handleNode(const OcTreeT::iterator &it)
hook that is called when traversing all nodes of the updated Octree (does nothing here) ...
virtual void publishAll(const ros::Time &rostime=ros::Time::now())
octomath::Vector3 point3d
bool readBinary(std::istream &s)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
static Time now()
virtual void handlePostNodeTraversal(const ros::Time &rostime)
hook that is called after traversing all nodes
boost::recursive_mutex m_config_mutex
nav_msgs::OccupancyGrid m_gridmap
float logodds(double probability)
virtual void update2DMap(const OcTreeT::iterator &it, bool occupied)
updates the downprojected 2D map as either occupied or free
#define ROS_ERROR_STREAM(args)
ros::ServiceServer m_resetService
unsigned mapIdx(int i, int j) const
pcl::PointCloud< pcl::PointXYZ > PCLPointCloud
Definition: OctomapServer.h:90
virtual void handleNodeInBBX(const OcTreeT::iterator &it)
hook that is called when traversing all nodes of the updated Octree in the updated area (does nothing...
#define ROS_ERROR(...)
bool isNodeOccupied(const OcTreeNode *occupancyNode) const
void filterGroundPlane(const PCLPointCloud &pc, PCLPointCloud &ground, PCLPointCloud &nonground) const
label the input cloud "pc" into ground and nonground. Should be in the robot&#39;s fixed frame (not world...
virtual void handleFreeNode(const OcTreeT::iterator &it)
hook that is called when traversing free nodes of the updated Octree
virtual bool openFile(const std::string &filename)
virtual void handleOccupiedNodeInBBX(const OcTreeT::iterator &it)
hook that is called when traversing occupied nodes in the updated area (updates 2D map projection her...
ros::ServiceServer m_clearBBXService
void setClampingThresMin(double thresProb)
Connection registerCallback(const C &callback)
#define ROS_DEBUG(...)


octomap_server
Author(s): Armin Hornung
autogenerated on Tue Jan 26 2021 03:27:07