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