OctomapServer.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010-2013, A. Hornung, University of Freiburg
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the University of Freiburg nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <octomap_server/OctomapServer.h>
00031 
00032 using namespace octomap;
00033 using octomap_msgs::Octomap;
00034 
00035 namespace octomap_server{
00036 
00037 OctomapServer::OctomapServer(ros::NodeHandle private_nh_)
00038 : m_nh(),
00039   m_pointCloudSub(NULL),
00040   m_tfPointCloudSub(NULL),
00041   m_octree(NULL),
00042   m_maxRange(-1.0),
00043   m_worldFrameId("/map"), m_baseFrameId("base_footprint"),
00044   m_useHeightMap(true),
00045   m_colorFactor(0.8),
00046   m_latchedTopics(true),
00047   m_publishFreeSpace(false),
00048   m_res(0.05),
00049   m_treeDepth(0),
00050   m_maxTreeDepth(0),
00051   m_probHit(0.7), m_probMiss(0.4),
00052   m_thresMin(0.12), m_thresMax(0.97),
00053   m_pointcloudMinZ(-std::numeric_limits<double>::max()),
00054   m_pointcloudMaxZ(std::numeric_limits<double>::max()),
00055   m_occupancyMinZ(-std::numeric_limits<double>::max()),
00056   m_occupancyMaxZ(std::numeric_limits<double>::max()),
00057   m_minSizeX(0.0), m_minSizeY(0.0),
00058   m_filterSpeckles(false), m_filterGroundPlane(false),
00059   m_groundFilterDistance(0.04), m_groundFilterAngle(0.15), m_groundFilterPlaneDistance(0.07),
00060   m_compressMap(true),
00061   m_incrementalUpdate(false)
00062 {
00063   ros::NodeHandle private_nh(private_nh_);
00064   private_nh.param("frame_id", m_worldFrameId, m_worldFrameId);
00065   private_nh.param("base_frame_id", m_baseFrameId, m_baseFrameId);
00066   private_nh.param("height_map", m_useHeightMap, m_useHeightMap);
00067   private_nh.param("color_factor", m_colorFactor, m_colorFactor);
00068 
00069   private_nh.param("pointcloud_min_z", m_pointcloudMinZ,m_pointcloudMinZ);
00070   private_nh.param("pointcloud_max_z", m_pointcloudMaxZ,m_pointcloudMaxZ);
00071   private_nh.param("occupancy_min_z", m_occupancyMinZ,m_occupancyMinZ);
00072   private_nh.param("occupancy_max_z", m_occupancyMaxZ,m_occupancyMaxZ);
00073   private_nh.param("min_x_size", m_minSizeX,m_minSizeX);
00074   private_nh.param("min_y_size", m_minSizeY,m_minSizeY);
00075 
00076   private_nh.param("filter_speckles", m_filterSpeckles, m_filterSpeckles);
00077   private_nh.param("filter_ground", m_filterGroundPlane, m_filterGroundPlane);
00078   // distance of points from plane for RANSAC
00079   private_nh.param("ground_filter/distance", m_groundFilterDistance, m_groundFilterDistance);
00080   // angular derivation of found plane:
00081   private_nh.param("ground_filter/angle", m_groundFilterAngle, m_groundFilterAngle);
00082   // distance of found plane from z=0 to be detected as ground (e.g. to exclude tables)
00083   private_nh.param("ground_filter/plane_distance", m_groundFilterPlaneDistance, m_groundFilterPlaneDistance);
00084 
00085   private_nh.param("sensor_model/max_range", m_maxRange, m_maxRange);
00086 
00087   private_nh.param("resolution", m_res, m_res);
00088   private_nh.param("sensor_model/hit", m_probHit, m_probHit);
00089   private_nh.param("sensor_model/miss", m_probMiss, m_probMiss);
00090   private_nh.param("sensor_model/min", m_thresMin, m_thresMin);
00091   private_nh.param("sensor_model/max", m_thresMax, m_thresMax);
00092   private_nh.param("compress_map", m_compressMap, m_compressMap);
00093   private_nh.param("incremental_2D_projection", m_incrementalUpdate, m_incrementalUpdate);
00094 
00095   if (m_filterGroundPlane && (m_pointcloudMinZ > 0.0 || m_pointcloudMaxZ < 0.0)){
00096           ROS_WARN_STREAM("You enabled ground filtering but incoming pointclouds will be pre-filtered in ["
00097                           <<m_pointcloudMinZ <<", "<< m_pointcloudMaxZ << "], excluding the ground level z=0. "
00098                           << "This will not work.");
00099 
00100   }
00101 
00102 
00103 
00104   // initialize octomap object & params
00105   m_octree = new OcTree(m_res);
00106   m_octree->setProbHit(m_probHit);
00107   m_octree->setProbMiss(m_probMiss);
00108   m_octree->setClampingThresMin(m_thresMin);
00109   m_octree->setClampingThresMax(m_thresMax);
00110   m_treeDepth = m_octree->getTreeDepth();
00111   m_maxTreeDepth = m_treeDepth;
00112   m_gridmap.info.resolution = m_res;
00113 
00114   double r, g, b, a;
00115   private_nh.param("color/r", r, 0.0);
00116   private_nh.param("color/g", g, 0.0);
00117   private_nh.param("color/b", b, 1.0);
00118   private_nh.param("color/a", a, 1.0);
00119   m_color.r = r;
00120   m_color.g = g;
00121   m_color.b = b;
00122   m_color.a = a;
00123 
00124   private_nh.param("color_free/r", r, 0.0);
00125   private_nh.param("color_free/g", g, 1.0);
00126   private_nh.param("color_free/b", b, 0.0);
00127   private_nh.param("color_free/a", a, 1.0);
00128   m_colorFree.r = r;
00129   m_colorFree.g = g;
00130   m_colorFree.b = b;
00131   m_colorFree.a = a;
00132 
00133   private_nh.param("publish_free_space", m_publishFreeSpace, m_publishFreeSpace);
00134 
00135   private_nh.param("latch", m_latchedTopics, m_latchedTopics);
00136   if (m_latchedTopics){
00137     ROS_INFO("Publishing latched (single publish will take longer, all topics are prepared)");
00138   } else
00139     ROS_INFO("Publishing non-latched (topics are only prepared as needed, will only be re-published on map change");
00140 
00141   m_markerPub = m_nh.advertise<visualization_msgs::MarkerArray>("occupied_cells_vis_array", 1, m_latchedTopics);
00142   m_binaryMapPub = m_nh.advertise<Octomap>("octomap_binary", 1, m_latchedTopics);
00143   m_fullMapPub = m_nh.advertise<Octomap>("octomap_full", 1, m_latchedTopics);
00144   m_pointCloudPub = m_nh.advertise<sensor_msgs::PointCloud2>("octomap_point_cloud_centers", 1, m_latchedTopics);
00145   m_mapPub = m_nh.advertise<nav_msgs::OccupancyGrid>("projected_map", 5, m_latchedTopics);      
00146   m_fmarkerPub = m_nh.advertise<visualization_msgs::MarkerArray>("free_cells_vis_array", 1, m_latchedTopics);
00147 
00148   m_pointCloudSub = new message_filters::Subscriber<sensor_msgs::PointCloud2> (m_nh, "cloud_in", 5);
00149   m_tfPointCloudSub = new tf::MessageFilter<sensor_msgs::PointCloud2> (*m_pointCloudSub, m_tfListener, m_worldFrameId, 5);
00150   m_tfPointCloudSub->registerCallback(boost::bind(&OctomapServer::insertCloudCallback, this, _1));
00151 
00152   m_octomapBinaryService = m_nh.advertiseService("octomap_binary", &OctomapServer::octomapBinarySrv, this);
00153   m_octomapFullService = m_nh.advertiseService("octomap_full", &OctomapServer::octomapFullSrv, this);
00154   m_clearBBXService = private_nh.advertiseService("clear_bbx", &OctomapServer::clearBBXSrv, this);
00155   m_resetService = private_nh.advertiseService("reset", &OctomapServer::resetSrv, this);
00156 
00157   dynamic_reconfigure::Server<OctomapServerConfig>::CallbackType f;
00158 
00159   f = boost::bind(&OctomapServer::reconfigureCallback, this, _1, _2);
00160   m_reconfigureServer.setCallback(f);
00161 }
00162 
00163 OctomapServer::~OctomapServer(){
00164   if (m_tfPointCloudSub){
00165     delete m_tfPointCloudSub;
00166     m_tfPointCloudSub = NULL;
00167   }
00168 
00169   if (m_pointCloudSub){
00170     delete m_pointCloudSub;
00171     m_pointCloudSub = NULL;
00172   }
00173 
00174 
00175   if (m_octree){
00176     delete m_octree;
00177     m_octree = NULL;
00178   }
00179 
00180 }
00181 
00182 bool OctomapServer::openFile(const std::string& filename){
00183   if (filename.length() <= 3)
00184     return false;
00185 
00186   std::string suffix = filename.substr(filename.length()-3, 3);
00187   if (suffix== ".bt"){
00188     if (!m_octree->readBinary(filename)){
00189       return false;
00190     }
00191   } else if (suffix == ".ot"){
00192     AbstractOcTree* tree = AbstractOcTree::read(filename);
00193     if (!tree){
00194       return false;
00195     }
00196     if (m_octree){
00197       delete m_octree;
00198       m_octree = NULL;
00199     }
00200     m_octree = dynamic_cast<OcTree*>(tree);
00201     if (!m_octree){
00202       ROS_ERROR("Could not read OcTree in file, currently there are no other types supported in .ot");
00203       return false;
00204     }
00205 
00206   } else{
00207     return false;
00208   }
00209 
00210   ROS_INFO("Octomap file %s loaded (%zu nodes).", filename.c_str(),m_octree->size());
00211 
00212   m_treeDepth = m_octree->getTreeDepth();
00213   m_maxTreeDepth = m_treeDepth;
00214   m_res = m_octree->getResolution();
00215   m_gridmap.info.resolution = m_res;
00216   double minX, minY, minZ;
00217   double maxX, maxY, maxZ;
00218   m_octree->getMetricMin(minX, minY, minZ);
00219   m_octree->getMetricMax(maxX, maxY, maxZ);
00220 
00221   m_updateBBXMin[0] = m_octree->coordToKey(minX);
00222   m_updateBBXMin[1] = m_octree->coordToKey(minY);
00223   m_updateBBXMin[2] = m_octree->coordToKey(minZ);
00224   
00225   m_updateBBXMax[0] = m_octree->coordToKey(maxX);
00226   m_updateBBXMax[1] = m_octree->coordToKey(maxY);
00227   m_updateBBXMax[2] = m_octree->coordToKey(maxZ);
00228   
00229   publishAll();
00230 
00231   return true;
00232 
00233 }
00234 
00235 void OctomapServer::insertCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& cloud){
00236   ros::WallTime startTime = ros::WallTime::now();
00237 
00238 
00239   //
00240   // ground filtering in base frame
00241   //
00242   PCLPointCloud pc; // input cloud for filtering and ground-detection
00243   pcl::fromROSMsg(*cloud, pc);
00244 
00245   tf::StampedTransform sensorToWorldTf;
00246   try {
00247     m_tfListener.lookupTransform(m_worldFrameId, cloud->header.frame_id, cloud->header.stamp, sensorToWorldTf);
00248   } catch(tf::TransformException& ex){
00249     ROS_ERROR_STREAM( "Transform error of sensor data: " << ex.what() << ", quitting callback");
00250     return;
00251   }
00252 
00253   Eigen::Matrix4f sensorToWorld;
00254   pcl_ros::transformAsMatrix(sensorToWorldTf, sensorToWorld);
00255 
00256 
00257   // set up filter for height range, also removes NANs:
00258   pcl::PassThrough<pcl::PointXYZ> pass;
00259   pass.setFilterFieldName("z");
00260   pass.setFilterLimits(m_pointcloudMinZ, m_pointcloudMaxZ);
00261 
00262   PCLPointCloud pc_ground; // segmented ground plane
00263   PCLPointCloud pc_nonground; // everything else
00264 
00265   if (m_filterGroundPlane){
00266     tf::StampedTransform sensorToBaseTf, baseToWorldTf;
00267     try{
00268       m_tfListener.waitForTransform(m_baseFrameId, cloud->header.frame_id, cloud->header.stamp, ros::Duration(0.2));
00269       m_tfListener.lookupTransform(m_baseFrameId, cloud->header.frame_id, cloud->header.stamp, sensorToBaseTf);
00270       m_tfListener.lookupTransform(m_worldFrameId, m_baseFrameId, cloud->header.stamp, baseToWorldTf);
00271 
00272 
00273     }catch(tf::TransformException& ex){
00274       ROS_ERROR_STREAM( "Transform error for ground plane filter: " << ex.what() << ", quitting callback.\n"
00275                         "You need to set the base_frame_id or disable filter_ground.");
00276     }
00277 
00278 
00279     Eigen::Matrix4f sensorToBase, baseToWorld;
00280     pcl_ros::transformAsMatrix(sensorToBaseTf, sensorToBase);
00281     pcl_ros::transformAsMatrix(baseToWorldTf, baseToWorld);
00282 
00283     // transform pointcloud from sensor frame to fixed robot frame
00284     pcl::transformPointCloud(pc, pc, sensorToBase);
00285     pass.setInputCloud(pc.makeShared());
00286     pass.filter(pc);
00287     filterGroundPlane(pc, pc_ground, pc_nonground);
00288 
00289     // transform clouds to world frame for insertion
00290     pcl::transformPointCloud(pc_ground, pc_ground, baseToWorld);
00291     pcl::transformPointCloud(pc_nonground, pc_nonground, baseToWorld);
00292   } else {
00293     // directly transform to map frame:
00294     pcl::transformPointCloud(pc, pc, sensorToWorld);
00295 
00296     // just filter height range:
00297     pass.setInputCloud(pc.makeShared());
00298     pass.filter(pc);
00299 
00300     pc_nonground = pc;
00301     // pc_nonground is empty without ground segmentation
00302     pc_ground.header = pc.header;
00303     pc_nonground.header = pc.header;
00304   }
00305 
00306 
00307   insertScan(sensorToWorldTf.getOrigin(), pc_ground, pc_nonground);
00308 
00309   double total_elapsed = (ros::WallTime::now() - startTime).toSec();
00310   ROS_DEBUG("Pointcloud insertion in OctomapServer done (%zu+%zu pts (ground/nonground), %f sec)", pc_ground.size(), pc_nonground.size(), total_elapsed);
00311 
00312   publishAll(cloud->header.stamp);
00313 }
00314 
00315 void OctomapServer::insertScan(const tf::Point& sensorOriginTf, const PCLPointCloud& ground, const PCLPointCloud& nonground){
00316   point3d sensorOrigin = pointTfToOctomap(sensorOriginTf);
00317 
00318   if (!m_octree->coordToKeyChecked(sensorOrigin, m_updateBBXMin)
00319     || !m_octree->coordToKeyChecked(sensorOrigin, m_updateBBXMax))
00320   {
00321     ROS_ERROR_STREAM("Could not generate Key for origin "<<sensorOrigin);
00322   }
00323 
00324 
00325 
00326   // instead of direct scan insertion, compute update to filter ground:
00327   KeySet free_cells, occupied_cells;
00328   // insert ground points only as free:
00329   for (PCLPointCloud::const_iterator it = ground.begin(); it != ground.end(); ++it){
00330     point3d point(it->x, it->y, it->z);
00331     // maxrange check
00332     if ((m_maxRange > 0.0) && ((point - sensorOrigin).norm() > m_maxRange) ) {
00333       point = sensorOrigin + (point - sensorOrigin).normalized() * m_maxRange;
00334     }
00335 
00336     // only clear space (ground points)
00337     if (m_octree->computeRayKeys(sensorOrigin, point, m_keyRay)){
00338       free_cells.insert(m_keyRay.begin(), m_keyRay.end());
00339     }
00340 
00341     octomap::OcTreeKey endKey;
00342     if (m_octree->coordToKeyChecked(point, endKey)){
00343       updateMinKey(endKey, m_updateBBXMin);
00344       updateMaxKey(endKey, m_updateBBXMax);
00345     } else{
00346       ROS_ERROR_STREAM("Could not generate Key for endpoint "<<point);
00347     }
00348   }
00349 
00350   // all other points: free on ray, occupied on endpoint:
00351   for (PCLPointCloud::const_iterator it = nonground.begin(); it != nonground.end(); ++it){
00352     point3d point(it->x, it->y, it->z);
00353     // maxrange check
00354     if ((m_maxRange < 0.0) || ((point - sensorOrigin).norm() <= m_maxRange) ) {
00355 
00356       // free cells
00357       if (m_octree->computeRayKeys(sensorOrigin, point, m_keyRay)){
00358         free_cells.insert(m_keyRay.begin(), m_keyRay.end());
00359       }
00360       // occupied endpoint
00361       OcTreeKey key;
00362       if (m_octree->coordToKeyChecked(point, key)){
00363         occupied_cells.insert(key);
00364 
00365         updateMinKey(key, m_updateBBXMin);
00366         updateMaxKey(key, m_updateBBXMax);
00367       }
00368     } else {// ray longer than maxrange:;
00369       point3d new_end = sensorOrigin + (point - sensorOrigin).normalized() * m_maxRange;
00370       if (m_octree->computeRayKeys(sensorOrigin, new_end, m_keyRay)){
00371         free_cells.insert(m_keyRay.begin(), m_keyRay.end());
00372 
00373         octomap::OcTreeKey endKey;
00374         if (m_octree->coordToKeyChecked(new_end, endKey)){
00375           updateMinKey(endKey, m_updateBBXMin);
00376           updateMaxKey(endKey, m_updateBBXMax);
00377         } else{
00378           ROS_ERROR_STREAM("Could not generate Key for endpoint "<<new_end);
00379         }
00380 
00381 
00382       }
00383     }
00384   }
00385 
00386   // mark free cells only if not seen occupied in this cloud
00387   for(KeySet::iterator it = free_cells.begin(), end=free_cells.end(); it!= end; ++it){
00388     if (occupied_cells.find(*it) == occupied_cells.end()){
00389       m_octree->updateNode(*it, false);
00390     }
00391   }
00392 
00393   // now mark all occupied cells:
00394   for (KeySet::iterator it = occupied_cells.begin(), end=free_cells.end(); it!= end; it++) {
00395     m_octree->updateNode(*it, true);
00396   }
00397 
00398   // TODO: eval lazy+updateInner vs. proper insertion
00399   // non-lazy by default (updateInnerOccupancy() too slow for large maps)
00400   //m_octree->updateInnerOccupancy();
00401   octomap::point3d minPt, maxPt;
00402   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]);
00403 
00404   // TODO: snap max / min keys to larger voxels by m_maxTreeDepth
00405 //   if (m_maxTreeDepth < 16)
00406 //   {
00407 //      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)
00408 //      OcTreeKey tmpMax = getIndexKey(m_updateBBXMax, m_maxTreeDepth); // see above, now add something to find upper right
00409 //      tmpMax[0]+= m_octree->getNodeSize( m_maxTreeDepth ) - 1;
00410 //      tmpMax[1]+= m_octree->getNodeSize( m_maxTreeDepth ) - 1;
00411 //      tmpMax[2]+= m_octree->getNodeSize( m_maxTreeDepth ) - 1;
00412 //      m_updateBBXMin = tmpMin;
00413 //      m_updateBBXMax = tmpMax;
00414 //   }
00415 
00416   // TODO: we could also limit the bbx to be within the map bounds here (see publishing check)
00417   minPt = m_octree->keyToCoord(m_updateBBXMin);
00418   maxPt = m_octree->keyToCoord(m_updateBBXMax);
00419   ROS_DEBUG_STREAM("Updated area bounding box: "<< minPt << " - "<<maxPt);
00420   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]);
00421 
00422   if (m_compressMap)
00423     m_octree->prune();
00424 
00425 
00426 }
00427 
00428 
00429 
00430 void OctomapServer::publishAll(const ros::Time& rostime){
00431   ros::WallTime startTime = ros::WallTime::now();
00432   size_t octomapSize = m_octree->size();
00433   // TODO: estimate num occ. voxels for size of arrays (reserve)
00434   if (octomapSize <= 1){
00435     ROS_WARN("Nothing to publish, octree is empty");
00436     return;
00437   }
00438 
00439   bool publishFreeMarkerArray = m_publishFreeSpace && (m_latchedTopics || m_fmarkerPub.getNumSubscribers() > 0);
00440   bool publishMarkerArray = (m_latchedTopics || m_markerPub.getNumSubscribers() > 0);
00441   bool publishPointCloud = (m_latchedTopics || m_pointCloudPub.getNumSubscribers() > 0);
00442   bool publishBinaryMap = (m_latchedTopics || m_binaryMapPub.getNumSubscribers() > 0);
00443   bool publishFullMap = (m_latchedTopics || m_fullMapPub.getNumSubscribers() > 0);
00444   m_publish2DMap = (m_latchedTopics || m_mapPub.getNumSubscribers() > 0);
00445 
00446   // init markers for free space:
00447   visualization_msgs::MarkerArray freeNodesVis;
00448   // each array stores all cubes of a different size, one for each depth level:
00449   freeNodesVis.markers.resize(m_treeDepth+1);
00450 
00451   geometry_msgs::Pose pose;
00452   pose.orientation = tf::createQuaternionMsgFromYaw(0.0);
00453 
00454   // init markers:
00455   visualization_msgs::MarkerArray occupiedNodesVis;
00456   // each array stores all cubes of a different size, one for each depth level:
00457   occupiedNodesVis.markers.resize(m_treeDepth+1);
00458 
00459   // init pointcloud:
00460   pcl::PointCloud<pcl::PointXYZ> pclCloud;
00461 
00462   // call pre-traversal hook:
00463   handlePreNodeTraversal(rostime);
00464 
00465   // now, traverse all leafs in the tree:
00466   for (OcTree::iterator it = m_octree->begin(m_maxTreeDepth),
00467       end = m_octree->end(); it != end; ++it)
00468   {
00469     bool inUpdateBBX = isInUpdateBBX(it);
00470 
00471     // call general hook:
00472     handleNode(it);
00473     if (inUpdateBBX)
00474       handleNodeInBBX(it);
00475 
00476     if (m_octree->isNodeOccupied(*it)){
00477       double z = it.getZ();
00478       if (z > m_occupancyMinZ && z < m_occupancyMaxZ)
00479       {
00480         double size = it.getSize();
00481         double x = it.getX();
00482         double y = it.getY();
00483 
00484         // Ignore speckles in the map:
00485         if (m_filterSpeckles && (it.getDepth() == m_treeDepth +1) && isSpeckleNode(it.getKey())){
00486           ROS_DEBUG("Ignoring single speckle at (%f,%f,%f)", x, y, z);
00487           continue;
00488         } // else: current octree node is no speckle, send it out
00489 
00490         handleOccupiedNode(it);
00491         if (inUpdateBBX)
00492           handleOccupiedNodeInBBX(it);
00493 
00494 
00495         //create marker:
00496         if (publishMarkerArray){
00497           unsigned idx = it.getDepth();
00498           assert(idx < occupiedNodesVis.markers.size());
00499 
00500           geometry_msgs::Point cubeCenter;
00501           cubeCenter.x = x;
00502           cubeCenter.y = y;
00503           cubeCenter.z = z;
00504 
00505           occupiedNodesVis.markers[idx].points.push_back(cubeCenter);
00506           if (m_useHeightMap){
00507             double minX, minY, minZ, maxX, maxY, maxZ;
00508             m_octree->getMetricMin(minX, minY, minZ);
00509             m_octree->getMetricMax(maxX, maxY, maxZ);
00510 
00511             double h = (1.0 - std::min(std::max((cubeCenter.z-minZ)/ (maxZ - minZ), 0.0), 1.0)) *m_colorFactor;
00512             occupiedNodesVis.markers[idx].colors.push_back(heightMapColor(h));
00513           }
00514         }
00515 
00516         // insert into pointcloud:
00517         if (publishPointCloud)
00518           pclCloud.push_back(pcl::PointXYZ(x, y, z));
00519 
00520       }
00521     } else{ // node not occupied => mark as free in 2D map if unknown so far
00522       double z = it.getZ();
00523       if (z > m_occupancyMinZ && z < m_occupancyMaxZ)
00524       {
00525         handleFreeNode(it);
00526         if (inUpdateBBX)
00527           handleFreeNodeInBBX(it);
00528 
00529         if (m_publishFreeSpace){
00530           double x = it.getX();
00531           double y = it.getY();
00532 
00533           //create marker for free space:
00534           if (publishFreeMarkerArray){
00535             unsigned idx = it.getDepth();
00536             assert(idx < freeNodesVis.markers.size());
00537 
00538             geometry_msgs::Point cubeCenter;
00539             cubeCenter.x = x;
00540             cubeCenter.y = y;
00541             cubeCenter.z = z;
00542 
00543             freeNodesVis.markers[idx].points.push_back(cubeCenter);
00544           }
00545         }
00546 
00547       }
00548     }
00549   }
00550 
00551   // call post-traversal hook:
00552   handlePostNodeTraversal(rostime);
00553 
00554   // finish MarkerArray:
00555   if (publishMarkerArray){
00556     for (unsigned i= 0; i < occupiedNodesVis.markers.size(); ++i){
00557       double size = m_octree->getNodeSize(i);
00558 
00559       occupiedNodesVis.markers[i].header.frame_id = m_worldFrameId;
00560       occupiedNodesVis.markers[i].header.stamp = rostime;
00561       occupiedNodesVis.markers[i].ns = "map";
00562       occupiedNodesVis.markers[i].id = i;
00563       occupiedNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
00564       occupiedNodesVis.markers[i].scale.x = size;
00565       occupiedNodesVis.markers[i].scale.y = size;
00566       occupiedNodesVis.markers[i].scale.z = size;
00567       occupiedNodesVis.markers[i].color = m_color;
00568 
00569 
00570       if (occupiedNodesVis.markers[i].points.size() > 0)
00571         occupiedNodesVis.markers[i].action = visualization_msgs::Marker::ADD;
00572       else
00573         occupiedNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
00574     }
00575 
00576     m_markerPub.publish(occupiedNodesVis);
00577   }
00578 
00579 
00580   // finish FreeMarkerArray:
00581   if (publishFreeMarkerArray){
00582     for (unsigned i= 0; i < freeNodesVis.markers.size(); ++i){
00583       double size = m_octree->getNodeSize(i);
00584 
00585       freeNodesVis.markers[i].header.frame_id = m_worldFrameId;
00586       freeNodesVis.markers[i].header.stamp = rostime;
00587       freeNodesVis.markers[i].ns = "map";
00588       freeNodesVis.markers[i].id = i;
00589       freeNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
00590       freeNodesVis.markers[i].scale.x = size;
00591       freeNodesVis.markers[i].scale.y = size;
00592       freeNodesVis.markers[i].scale.z = size;
00593       freeNodesVis.markers[i].color = m_colorFree;
00594 
00595 
00596       if (freeNodesVis.markers[i].points.size() > 0)
00597         freeNodesVis.markers[i].action = visualization_msgs::Marker::ADD;
00598       else
00599         freeNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
00600     }
00601 
00602     m_fmarkerPub.publish(freeNodesVis);
00603   }
00604 
00605 
00606   // finish pointcloud:
00607   if (publishPointCloud){
00608     sensor_msgs::PointCloud2 cloud;
00609     pcl::toROSMsg (pclCloud, cloud);
00610     cloud.header.frame_id = m_worldFrameId;
00611     cloud.header.stamp = rostime;
00612     m_pointCloudPub.publish(cloud);
00613   }
00614 
00615   if (publishBinaryMap)
00616     publishBinaryOctoMap(rostime);
00617 
00618   if (publishFullMap)
00619     publishFullOctoMap(rostime);
00620 
00621 
00622   double total_elapsed = (ros::WallTime::now() - startTime).toSec();
00623   ROS_DEBUG("Map publishing in OctomapServer took %f sec", total_elapsed);
00624 
00625 }
00626 
00627 
00628 bool OctomapServer::octomapBinarySrv(OctomapSrv::Request  &req,
00629                                     OctomapSrv::Response &res)
00630 {
00631   ROS_INFO("Sending binary map data on service request");
00632   res.map.header.frame_id = m_worldFrameId;
00633   res.map.header.stamp = ros::Time::now();
00634   if (!octomap_msgs::binaryMapToMsg(*m_octree, res.map))
00635     return false;
00636 
00637   return true;
00638 }
00639 
00640 bool OctomapServer::octomapFullSrv(OctomapSrv::Request  &req,
00641                                     OctomapSrv::Response &res)
00642 {
00643   ROS_INFO("Sending full map data on service request");
00644   res.map.header.frame_id = m_worldFrameId;
00645   res.map.header.stamp = ros::Time::now();
00646 
00647 
00648   if (!octomap_msgs::fullMapToMsg(*m_octree, res.map))
00649     return false;
00650 
00651   return true;
00652 }
00653 
00654 bool OctomapServer::clearBBXSrv(BBXSrv::Request& req, BBXSrv::Response& resp){
00655   point3d min = pointMsgToOctomap(req.min);
00656   point3d max = pointMsgToOctomap(req.max);
00657 
00658   for(OcTree::leaf_bbx_iterator it = m_octree->begin_leafs_bbx(min,max),
00659       end=m_octree->end_leafs_bbx(); it!= end; ++it){
00660 
00661     it->setLogOdds(octomap::logodds(m_thresMin));
00662     //                  m_octree->updateNode(it.getKey(), -6.0f);
00663   }
00664   // TODO: eval which is faster (setLogOdds+updateInner or updateNode)
00665   m_octree->updateInnerOccupancy();
00666 
00667   publishAll(ros::Time::now());
00668 
00669   return true;
00670 }
00671 
00672 bool OctomapServer::resetSrv(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp) {
00673   visualization_msgs::MarkerArray occupiedNodesVis;
00674   occupiedNodesVis.markers.resize(m_treeDepth +1);
00675   ros::Time rostime = ros::Time::now();
00676   m_octree->clear();
00677   // clear 2D map:
00678   m_gridmap.data.clear();
00679   m_gridmap.info.height = 0.0;
00680   m_gridmap.info.width = 0.0;
00681   m_gridmap.info.resolution = 0.0;
00682   m_gridmap.info.origin.position.x = 0.0;
00683   m_gridmap.info.origin.position.y = 0.0;
00684 
00685   ROS_INFO("Cleared octomap");
00686   publishAll(rostime);
00687 
00688   publishBinaryOctoMap(rostime);
00689   for (unsigned i= 0; i < occupiedNodesVis.markers.size(); ++i){
00690 
00691     occupiedNodesVis.markers[i].header.frame_id = m_worldFrameId;
00692     occupiedNodesVis.markers[i].header.stamp = rostime;
00693     occupiedNodesVis.markers[i].ns = "map";
00694     occupiedNodesVis.markers[i].id = i;
00695     occupiedNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
00696     occupiedNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
00697   }
00698 
00699 
00700   m_markerPub.publish(occupiedNodesVis);
00701 
00702 
00703   visualization_msgs::MarkerArray freeNodesVis;
00704   freeNodesVis.markers.resize(m_treeDepth +1);
00705 
00706   for (unsigned i= 0; i < freeNodesVis.markers.size(); ++i){
00707 
00708     freeNodesVis.markers[i].header.frame_id = m_worldFrameId;
00709     freeNodesVis.markers[i].header.stamp = rostime;
00710     freeNodesVis.markers[i].ns = "map";
00711     freeNodesVis.markers[i].id = i;
00712     freeNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
00713     freeNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
00714   }
00715   m_fmarkerPub.publish(freeNodesVis);
00716 
00717   return true;
00718 }
00719 
00720 void OctomapServer::publishBinaryOctoMap(const ros::Time& rostime) const{
00721 
00722   Octomap map;
00723   map.header.frame_id = m_worldFrameId;
00724   map.header.stamp = rostime;
00725 
00726   if (octomap_msgs::binaryMapToMsg(*m_octree, map))
00727     m_binaryMapPub.publish(map);
00728   else
00729     ROS_ERROR("Error serializing OctoMap");
00730 }
00731 
00732 void OctomapServer::publishFullOctoMap(const ros::Time& rostime) const{
00733 
00734   Octomap map;
00735   map.header.frame_id = m_worldFrameId;
00736   map.header.stamp = rostime;
00737 
00738   if (octomap_msgs::fullMapToMsg(*m_octree, map))
00739     m_fullMapPub.publish(map);
00740   else
00741     ROS_ERROR("Error serializing OctoMap");
00742 
00743 }
00744 
00745 
00746 void OctomapServer::filterGroundPlane(const PCLPointCloud& pc, PCLPointCloud& ground, PCLPointCloud& nonground) const{
00747   ground.header = pc.header;
00748   nonground.header = pc.header;
00749 
00750   if (pc.size() < 50){
00751     ROS_WARN("Pointcloud in OctomapServer too small, skipping ground plane extraction");
00752     nonground = pc;
00753   } else {
00754     // plane detection for ground plane removal:
00755     pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
00756     pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
00757 
00758     // Create the segmentation object and set up:
00759     pcl::SACSegmentation<pcl::PointXYZ> seg;
00760     seg.setOptimizeCoefficients (true);
00761     // TODO: maybe a filtering based on the surface normals might be more robust / accurate?
00762     seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
00763     seg.setMethodType(pcl::SAC_RANSAC);
00764     seg.setMaxIterations(200);
00765     seg.setDistanceThreshold (m_groundFilterDistance);
00766     seg.setAxis(Eigen::Vector3f(0,0,1));
00767     seg.setEpsAngle(m_groundFilterAngle);
00768 
00769 
00770     PCLPointCloud cloud_filtered(pc);
00771     // Create the filtering object
00772     pcl::ExtractIndices<pcl::PointXYZ> extract;
00773     bool groundPlaneFound = false;
00774 
00775     while(cloud_filtered.size() > 10 && !groundPlaneFound){
00776       seg.setInputCloud(cloud_filtered.makeShared());
00777       seg.segment (*inliers, *coefficients);
00778       if (inliers->indices.size () == 0){
00779         ROS_INFO("PCL segmentation did not find any plane.");
00780 
00781         break;
00782       }
00783 
00784       extract.setInputCloud(cloud_filtered.makeShared());
00785       extract.setIndices(inliers);
00786 
00787       if (std::abs(coefficients->values.at(3)) < m_groundFilterPlaneDistance){
00788         ROS_DEBUG("Ground plane found: %zu/%zu inliers. Coeff: %f %f %f %f", inliers->indices.size(), cloud_filtered.size(),
00789                   coefficients->values.at(0), coefficients->values.at(1), coefficients->values.at(2), coefficients->values.at(3));
00790         extract.setNegative (false);
00791         extract.filter (ground);
00792 
00793         // remove ground points from full pointcloud:
00794         // workaround for PCL bug:
00795         if(inliers->indices.size() != cloud_filtered.size()){
00796           extract.setNegative(true);
00797           PCLPointCloud cloud_out;
00798           extract.filter(cloud_out);
00799           nonground += cloud_out;
00800           cloud_filtered = cloud_out;
00801         }
00802 
00803         groundPlaneFound = true;
00804       } else{
00805         ROS_DEBUG("Horizontal plane (not ground) found: %zu/%zu inliers. Coeff: %f %f %f %f", inliers->indices.size(), cloud_filtered.size(),
00806                   coefficients->values.at(0), coefficients->values.at(1), coefficients->values.at(2), coefficients->values.at(3));
00807         pcl::PointCloud<pcl::PointXYZ> cloud_out;
00808         extract.setNegative (false);
00809         extract.filter(cloud_out);
00810         nonground +=cloud_out;
00811         // debug
00812         //            pcl::PCDWriter writer;
00813         //            writer.write<pcl::PointXYZ>("nonground_plane.pcd",cloud_out, false);
00814 
00815         // remove current plane from scan for next iteration:
00816         // workaround for PCL bug:
00817         if(inliers->indices.size() != cloud_filtered.size()){
00818           extract.setNegative(true);
00819           cloud_out.points.clear();
00820           extract.filter(cloud_out);
00821           cloud_filtered = cloud_out;
00822         } else{
00823           cloud_filtered.points.clear();
00824         }
00825       }
00826 
00827     }
00828     // TODO: also do this if overall starting pointcloud too small?
00829     if (!groundPlaneFound){ // no plane found or remaining points too small
00830       ROS_WARN("No ground plane found in scan");
00831 
00832       // do a rough fitlering on height to prevent spurious obstacles
00833       pcl::PassThrough<pcl::PointXYZ> second_pass;
00834       second_pass.setFilterFieldName("z");
00835       second_pass.setFilterLimits(-m_groundFilterPlaneDistance, m_groundFilterPlaneDistance);
00836       second_pass.setInputCloud(pc.makeShared());
00837       second_pass.filter(ground);
00838 
00839       second_pass.setFilterLimitsNegative (true);
00840       second_pass.filter(nonground);
00841     }
00842 
00843     // debug:
00844     //        pcl::PCDWriter writer;
00845     //        if (pc_ground.size() > 0)
00846     //          writer.write<pcl::PointXYZ>("ground.pcd",pc_ground, false);
00847     //        if (pc_nonground.size() > 0)
00848     //          writer.write<pcl::PointXYZ>("nonground.pcd",pc_nonground, false);
00849 
00850   }
00851 
00852 
00853 }
00854 
00855 void OctomapServer::handlePreNodeTraversal(const ros::Time& rostime){
00856   if (m_publish2DMap){
00857     // init projected 2D map:
00858     m_gridmap.header.frame_id = m_worldFrameId;
00859     m_gridmap.header.stamp = rostime;
00860     nav_msgs::MapMetaData oldMapInfo = m_gridmap.info;
00861 
00862     // TODO: move most of this stuff into c'tor and init map only once (adjust if size changes)
00863     double minX, minY, minZ, maxX, maxY, maxZ;
00864     m_octree->getMetricMin(minX, minY, minZ);
00865     m_octree->getMetricMax(maxX, maxY, maxZ);
00866 
00867     octomap::point3d minPt(minX, minY, minZ);
00868     octomap::point3d maxPt(maxX, maxY, maxZ);
00869     octomap::OcTreeKey minKey = m_octree->coordToKey(minPt, m_maxTreeDepth);
00870     octomap::OcTreeKey maxKey = m_octree->coordToKey(maxPt, m_maxTreeDepth);
00871     
00872     ROS_DEBUG("MinKey: %d %d %d / MaxKey: %d %d %d", minKey[0], minKey[1], minKey[2], maxKey[0], maxKey[1], maxKey[2]);
00873 
00874     // add padding if requested (= new min/maxPts in x&y):
00875     double halfPaddedX = 0.5*m_minSizeX;
00876     double halfPaddedY = 0.5*m_minSizeY;
00877     minX = std::min(minX, -halfPaddedX);
00878     maxX = std::max(maxX, halfPaddedX);
00879     minY = std::min(minY, -halfPaddedY);
00880     maxY = std::max(maxY, halfPaddedY);
00881     minPt = octomap::point3d(minX, minY, minZ);
00882     maxPt = octomap::point3d(maxX, maxY, maxZ);
00883 
00884     OcTreeKey paddedMaxKey;
00885     if (!m_octree->coordToKeyChecked(minPt, m_maxTreeDepth, m_paddedMinKey)){
00886       ROS_ERROR("Could not create padded min OcTree key at %f %f %f", minPt.x(), minPt.y(), minPt.z());
00887       return;
00888     }
00889     if (!m_octree->coordToKeyChecked(maxPt, m_maxTreeDepth, paddedMaxKey)){
00890       ROS_ERROR("Could not create padded max OcTree key at %f %f %f", maxPt.x(), maxPt.y(), maxPt.z());
00891       return;
00892     }
00893 
00894     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]);
00895     assert(paddedMaxKey[0] >= maxKey[0] && paddedMaxKey[1] >= maxKey[1]);
00896 
00897     m_multires2DScale = 1 << (m_treeDepth - m_maxTreeDepth);
00898     m_gridmap.info.width = (paddedMaxKey[0] - m_paddedMinKey[0])/m_multires2DScale +1;
00899     m_gridmap.info.height = (paddedMaxKey[1] - m_paddedMinKey[1])/m_multires2DScale +1;
00900 
00901     int mapOriginX = minKey[0] - m_paddedMinKey[0];
00902     int mapOriginY = minKey[1] - m_paddedMinKey[1];
00903     assert(mapOriginX >= 0 && mapOriginY >= 0);
00904 
00905     // might not exactly be min / max of octree:
00906     octomap::point3d origin = m_octree->keyToCoord(m_paddedMinKey, m_treeDepth);
00907     double gridRes = m_octree->getNodeSize(m_maxTreeDepth);
00908     m_projectCompleteMap = (!m_incrementalUpdate || (std::abs(gridRes-m_gridmap.info.resolution) > 1e-6));
00909     m_gridmap.info.resolution = gridRes;
00910     m_gridmap.info.origin.position.x = origin.x() - gridRes*0.5;
00911     m_gridmap.info.origin.position.y = origin.y() - gridRes*0.5;
00912     if (m_maxTreeDepth != m_treeDepth){
00913       m_gridmap.info.origin.position.x -= m_res/2.0;
00914       m_gridmap.info.origin.position.y -= m_res/2.0;
00915     }
00916     
00917     // workaround for  multires. projection not working properly for inner nodes:
00918     // force re-building complete map
00919     if (m_maxTreeDepth < m_treeDepth)
00920       m_projectCompleteMap = true;
00921 
00922 
00923     if(m_projectCompleteMap){
00924       ROS_DEBUG("Rebuilding complete 2D map");
00925       m_gridmap.data.clear();
00926       // init to unknown:
00927       m_gridmap.data.resize(m_gridmap.info.width * m_gridmap.info.height, -1);
00928 
00929     } else {
00930 
00931        if (mapChanged(oldMapInfo, m_gridmap.info)){
00932           ROS_DEBUG("2D grid map size changed to %dx%d", m_gridmap.info.width, m_gridmap.info.height);
00933           adjustMapData(m_gridmap, oldMapInfo);
00934        }
00935        nav_msgs::OccupancyGrid::_data_type::iterator startIt;
00936        size_t mapUpdateBBXMinX = std::max(0, (int(m_updateBBXMin[0]) - int(m_paddedMinKey[0]))/int(m_multires2DScale));
00937        size_t mapUpdateBBXMinY = std::max(0, (int(m_updateBBXMin[1]) - int(m_paddedMinKey[1]))/int(m_multires2DScale));
00938        size_t mapUpdateBBXMaxX = std::min(int(m_gridmap.info.width-1), (int(m_updateBBXMax[0]) - int(m_paddedMinKey[0]))/int(m_multires2DScale));
00939        size_t mapUpdateBBXMaxY = std::min(int(m_gridmap.info.height-1), (int(m_updateBBXMax[1]) - int(m_paddedMinKey[1]))/int(m_multires2DScale));
00940 
00941        assert(mapUpdateBBXMaxX > mapUpdateBBXMinX);
00942        assert(mapUpdateBBXMaxY > mapUpdateBBXMinY);
00943 
00944        size_t numCols = mapUpdateBBXMaxX-mapUpdateBBXMinX +1;
00945 
00946        // test for max idx:
00947        uint max_idx = m_gridmap.info.width*mapUpdateBBXMaxY + mapUpdateBBXMaxX;
00948        if (max_idx  >= m_gridmap.data.size())
00949          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);
00950 
00951        // reset proj. 2D map in bounding box:
00952        for (unsigned int j = mapUpdateBBXMinY; j <= mapUpdateBBXMaxY; ++j){
00953           std::fill_n(m_gridmap.data.begin() + m_gridmap.info.width*j+mapUpdateBBXMinX,
00954                       numCols, -1);
00955        }
00956 
00957     }
00958        
00959 
00960 
00961   }
00962 
00963 }
00964 
00965 void OctomapServer::handlePostNodeTraversal(const ros::Time& rostime){
00966 
00967   if (m_publish2DMap)
00968     m_mapPub.publish(m_gridmap);
00969 }
00970 
00971 void OctomapServer::handleOccupiedNode(const OcTreeT::iterator& it){
00972 
00973   if (m_publish2DMap && m_projectCompleteMap){
00974     update2DMap(it, true);
00975   }
00976 }
00977 
00978 void OctomapServer::handleFreeNode(const OcTreeT::iterator& it){
00979 
00980   if (m_publish2DMap && m_projectCompleteMap){
00981     update2DMap(it, false);
00982   }
00983 }
00984 
00985 void OctomapServer::handleOccupiedNodeInBBX(const OcTreeT::iterator& it){
00986 
00987   if (m_publish2DMap && !m_projectCompleteMap){
00988     update2DMap(it, true);
00989   }
00990 }
00991 
00992 void OctomapServer::handleFreeNodeInBBX(const OcTreeT::iterator& it){
00993 
00994   if (m_publish2DMap && !m_projectCompleteMap){
00995     update2DMap(it, false);
00996   }
00997 }
00998 
00999 void OctomapServer::update2DMap(const OcTreeT::iterator& it, bool occupied){
01000 
01001   // update 2D map (occupied always overrides):
01002 
01003   if (it.getDepth() == m_maxTreeDepth){
01004     unsigned idx = mapIdx(it.getKey());
01005     if (occupied)
01006       m_gridmap.data[mapIdx(it.getKey())] = 100;
01007     else if (m_gridmap.data[idx] == -1){
01008       m_gridmap.data[idx] = 0;
01009     }
01010 
01011   } else{
01012     int intSize = 1 << (m_maxTreeDepth - it.getDepth());
01013     octomap::OcTreeKey minKey=it.getIndexKey();
01014     for(int dx=0; dx < intSize; dx++){
01015       int i = (minKey[0]+dx - m_paddedMinKey[0])/m_multires2DScale;
01016       for(int dy=0; dy < intSize; dy++){
01017         unsigned idx = mapIdx(i, (minKey[1]+dy - m_paddedMinKey[1])/m_multires2DScale);
01018         if (occupied)
01019           m_gridmap.data[idx] = 100;
01020         else if (m_gridmap.data[idx] == -1){
01021           m_gridmap.data[idx] = 0;
01022         }
01023       }
01024     }
01025   }
01026 
01027 
01028 }
01029 
01030 
01031 
01032 bool OctomapServer::isSpeckleNode(const OcTreeKey&nKey) const {
01033   OcTreeKey key;
01034   bool neighborFound = false;
01035   for (key[2] = nKey[2] - 1; !neighborFound && key[2] <= nKey[2] + 1; ++key[2]){
01036     for (key[1] = nKey[1] - 1; !neighborFound && key[1] <= nKey[1] + 1; ++key[1]){
01037       for (key[0] = nKey[0] - 1; !neighborFound && key[0] <= nKey[0] + 1; ++key[0]){
01038         if (key != nKey){
01039           OcTreeNode* node = m_octree->search(key);
01040           if (node && m_octree->isNodeOccupied(node)){
01041             // we have a neighbor => break!
01042             neighborFound = true;
01043           }
01044         }
01045       }
01046     }
01047   }
01048 
01049   return neighborFound;
01050 }
01051 
01052 void OctomapServer::reconfigureCallback(octomap_server::OctomapServerConfig& config, uint32_t level){
01053   if (m_maxTreeDepth != unsigned(config.max_depth)){
01054     m_maxTreeDepth = unsigned(config.max_depth);
01055 
01056     publishAll();
01057   }
01058 
01059 
01060 }
01061 
01062 void OctomapServer::adjustMapData(nav_msgs::OccupancyGrid& map, const nav_msgs::MapMetaData& oldMapInfo) const{
01063   if (map.info.resolution != oldMapInfo.resolution){
01064     ROS_ERROR("Resolution of map changed, cannot be adjusted");
01065     return;
01066   }
01067 
01068   int i_off = int((oldMapInfo.origin.position.x - map.info.origin.position.x)/map.info.resolution +0.5);
01069   int j_off = int((oldMapInfo.origin.position.y - map.info.origin.position.y)/map.info.resolution +0.5);
01070 
01071   if (i_off < 0 || j_off < 0
01072       || oldMapInfo.width  + i_off > map.info.width
01073       || oldMapInfo.height + j_off > map.info.height)
01074   {
01075     ROS_ERROR("New 2D map does not contain old map area, this case is not implemented");
01076     return;
01077   }
01078 
01079   nav_msgs::OccupancyGrid::_data_type oldMapData = map.data;
01080 
01081   map.data.clear();
01082   // init to unknown:
01083   map.data.resize(map.info.width * map.info.height, -1);
01084 
01085   nav_msgs::OccupancyGrid::_data_type::iterator fromStart, fromEnd, toStart;
01086 
01087   for (int j =0; j < int(oldMapInfo.height); ++j ){
01088     // copy chunks, row by row:
01089     fromStart = oldMapData.begin() + j*oldMapInfo.width;
01090     fromEnd = fromStart + oldMapInfo.width;
01091     toStart = map.data.begin() + ((j+j_off)*m_gridmap.info.width + i_off);
01092     copy(fromStart, fromEnd, toStart);
01093 
01094 //    for (int i =0; i < int(oldMapInfo.width); ++i){
01095 //      map.data[m_gridmap.info.width*(j+j_off) +i+i_off] = oldMapData[oldMapInfo.width*j +i];
01096 //    }
01097 
01098   }
01099 
01100 }
01101 
01102 
01103 std_msgs::ColorRGBA OctomapServer::heightMapColor(double h) {
01104 
01105   std_msgs::ColorRGBA color;
01106   color.a = 1.0;
01107   // blend over HSV-values (more colors)
01108 
01109   double s = 1.0;
01110   double v = 1.0;
01111 
01112   h -= floor(h);
01113   h *= 6;
01114   int i;
01115   double m, n, f;
01116 
01117   i = floor(h);
01118   f = h - i;
01119   if (!(i & 1))
01120     f = 1 - f; // if i is even
01121   m = v * (1 - s);
01122   n = v * (1 - s * f);
01123 
01124   switch (i) {
01125     case 6:
01126     case 0:
01127       color.r = v; color.g = n; color.b = m;
01128       break;
01129     case 1:
01130       color.r = n; color.g = v; color.b = m;
01131       break;
01132     case 2:
01133       color.r = m; color.g = v; color.b = n;
01134       break;
01135     case 3:
01136       color.r = m; color.g = n; color.b = v;
01137       break;
01138     case 4:
01139       color.r = n; color.g = m; color.b = v;
01140       break;
01141     case 5:
01142       color.r = v; color.g = m; color.b = n;
01143       break;
01144     default:
01145       color.r = 1; color.g = 0.5; color.b = 0.5;
01146       break;
01147   }
01148 
01149   return color;
01150 }
01151 }
01152 
01153 
01154 


octomap_server
Author(s): Armin Hornung
autogenerated on Thu Aug 27 2015 14:14:07