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


octomap_tensor_field
Author(s): Lintao Zheng
autogenerated on Thu Jun 6 2019 19:50:39