$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id:$ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by dcgm-robotics@FIT group. 00009 * 00010 * Author: Vit Stancl (stancl@fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: dd/mm/2012 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 00028 #include <srs_env_model/but_server/plugins/octomap_plugin.h> 00029 #include <srs_env_model/topics_list.h> 00030 #include <srs_env_model/but_server/plugins/point_cloud_plugin.h> 00031 00032 00033 #include <pcl_ros/transforms.h> 00034 #include <pcl/io/io.h> 00035 00036 // Filtering 00037 #include <visualization_msgs/MarkerArray.h> 00038 #include <visualization_msgs/Marker.h> 00039 00040 // Interactive marker 00041 #include <srs_interaction_primitives/AddUnknownObject.h> 00042 00043 #define DEFAULT_RESOLUTION 0.1 00044 00045 void srs_env_model::COctoMapPlugin::setDefaults() 00046 { 00047 // Set octomap parameters 00048 m_mapParameters.resolution = DEFAULT_RESOLUTION; 00049 m_mapParameters.treeDepth = 0; 00050 m_mapParameters.probHit = 0.7; // Probability of node, if node is occupied: 0.7 00051 m_mapParameters.probMiss = 0.4; // Probability of node, if node is free: 0.4 00052 m_mapParameters.thresMin = 0.12; // Clamping minimum threshold: 0.1192; 00053 m_mapParameters.thresMax = 0.97; // Clamping maximum threshold: 0.971; 00054 m_mapParameters.thresOccupancy = 0.5; // Occupied node threshold: 0.5 00055 m_mapParameters.maxRange = 7; 00056 00057 // Set ground filtering parameters 00058 m_filterGroundPlane = false; 00059 m_removeSpecles = false; 00060 m_mapParameters.frameId = "/map"; 00061 m_bPublishOctomap = true; 00062 00063 // Filtering 00064 m_bRemoveOutdated = true; 00065 m_removeTester = 0; //new CTestingPolymesh(CTestingPolymesh::tPoint( 1.0, 1.0, 0.5 ), quat, CTestingPolymesh::tPoint( 1.0, 1.5, 2.0 )); 00066 m_testerLife = 1; 00067 00068 // Set maximal tree depth used when crawling. Zero means maximal possible depth. 00069 m_crawlDepth = 0; 00070 m_bMapLoaded = false; 00071 m_bNotFirst = false; 00072 00073 m_probDeleted = m_mapParameters.probMiss * 0.1; 00074 m_r = m_g = m_b = 128; 00075 } 00076 00077 srs_env_model::COctoMapPlugin::COctoMapPlugin(const std::string & name) 00078 : srs_env_model::CServerPluginBase(name) 00079 , CDataHolderBase< tButServerOcMap >( new tButServerOcMap(DEFAULT_RESOLUTION) ) 00080 , filecounter(0) 00081 , m_filterSingleSpecles("/map") 00082 , m_filterRaycast("/map") 00083 , m_filterGround("/map") 00084 , m_bFilterWithInput(false) 00085 , m_bNewDataToFilter(false) 00086 , m_bMapLoaded(false) 00087 { 00088 // 00089 setDefaults(); 00090 00091 assert( m_data != 0 ); 00092 00093 // Set octomap parameters 00094 m_data->getTree().setProbHit(m_mapParameters.probHit); 00095 m_data->getTree().setProbMiss(m_mapParameters.probMiss); 00096 m_data->getTree().setClampingThresMin(m_mapParameters.thresMin); 00097 m_data->getTree().setClampingThresMax(m_mapParameters.thresMax); 00098 m_data->getTree().setOccupancyThres(m_mapParameters.thresOccupancy); 00099 m_mapParameters.treeDepth = m_data->getTree().getTreeDepth(); 00100 m_mapParameters.map = m_data; 00101 m_mapParameters.crawlDepth = m_crawlDepth; 00102 } 00103 00104 srs_env_model::COctoMapPlugin::COctoMapPlugin(const std::string & name, const std::string & filename) 00105 : srs_env_model::CServerPluginBase(name) 00106 , CDataHolderBase< tButServerOcMap >( new tButServerOcMap(DEFAULT_RESOLUTION) ) 00107 , m_filterSingleSpecles("/map") 00108 , m_filterRaycast("/map") 00109 , m_filterGround("/map") 00110 , m_bFilterWithInput(false) 00111 , m_filterCloudPlugin(new CPointCloudPlugin("PCFILTER", false )) 00112 , m_bNewDataToFilter(false) 00113 , m_bMapLoaded(false) 00114 { 00115 setDefaults(); 00116 00117 assert( m_data != 0 ); 00118 00119 // Set octomap parameters 00120 m_data->getTree().setProbHit(m_mapParameters.probHit); 00121 m_data->getTree().setProbMiss(m_mapParameters.probMiss); 00122 m_data->getTree().setClampingThresMin(m_mapParameters.thresMin); 00123 m_data->getTree().setClampingThresMax(m_mapParameters.thresMax); 00124 m_data->getTree().setOccupancyThres(m_mapParameters.thresOccupancy); 00125 m_mapParameters.treeDepth = m_data->getTree().getTreeDepth(); 00126 m_mapParameters.map = m_data; 00127 m_mapParameters.crawlDepth = m_crawlDepth; 00128 00129 // is filename valid? 00130 if (filename.length() > 0) { 00131 // Try to load data 00132 if (m_data->getTree().readBinary(filename)) { 00133 ROS_INFO("Octomap file %s loaded (%zu nodes).", filename.c_str(), m_data->getTree().size()); 00134 00135 // get tree depth 00136 m_mapParameters.treeDepth = m_data->getTree().getTreeDepth(); 00137 00138 // get resolution 00139 m_mapParameters.resolution = m_data->getTree().getResolution(); 00140 00141 // Map was loaded 00142 m_bMapLoaded = true; 00143 00144 // We have new data 00145 invalidate(); 00146 00147 } else { 00148 00149 // Something is wrong - cannot load data... 00150 ROS_ERROR("Could not open requested file %s, continuing in standard mode.", filename.c_str()); 00151 PERROR( "Transform error."); 00152 } 00153 } 00154 } 00155 00159 srs_env_model::COctoMapPlugin::~COctoMapPlugin()\ 00160 { 00161 // Remove tester 00162 if (m_removeTester != 0) 00163 delete m_removeTester; 00164 } 00165 00167 void srs_env_model::COctoMapPlugin::init(ros::NodeHandle & node_handle) 00168 { 00169 PERROR( "Initializing OctoMapPlugin" ); 00170 00171 reset(false); 00172 00173 node_handle.param("ocmap_resolution", m_mapParameters.resolution, 00174 m_mapParameters.resolution); 00175 int td( m_mapParameters.treeDepth); 00176 node_handle.param("ocmap_treedepth", td, td ); 00177 m_mapParameters.treeDepth = ( td < 0 ) ? 0 : td; 00178 node_handle.param("ocmap_sensor_model/hit", m_mapParameters.probHit, 00179 m_mapParameters.probHit); 00180 node_handle.param("ocmap_sensor_model/miss", m_mapParameters.probMiss, 00181 m_mapParameters.probMiss); 00182 node_handle.param("ocmap_sensor_model/min", m_mapParameters.thresMin, 00183 m_mapParameters.thresMin); 00184 node_handle.param("ocmap_sensor_model/max", m_mapParameters.thresMax, 00185 m_mapParameters.thresMax); 00186 node_handle.param("ocmap_max_range", m_mapParameters.maxRange, 00187 m_mapParameters.maxRange); 00188 00189 node_handle.param("ocmap_frame_id", m_mapParameters.frameId, m_mapParameters.frameId ); 00190 00191 // Set octomap parameters... 00192 { 00193 m_data->getTree().setResolution(m_mapParameters.resolution); 00194 m_data->getTree().setProbHit(m_mapParameters.probHit); 00195 m_data->getTree().setProbMiss(m_mapParameters.probMiss); 00196 m_data->getTree().setClampingThresMin(m_mapParameters.thresMin); 00197 m_data->getTree().setClampingThresMax(m_mapParameters.thresMax); 00198 } 00199 00200 // Default color 00201 int c; 00202 c = m_r; node_handle.param("pointcloud_default_color_r", c, c); m_r = c; 00203 c = m_g; node_handle.param("pointcloud_default_color_g", c, c); m_g = c; 00204 c = m_b; node_handle.param("pointcloud_default_color_b", c, c); m_b = c; 00205 00206 // Should ground plane be filtered? 00207 node_handle.param("ocmap_filter_ground", m_filterGroundPlane, m_filterGroundPlane); 00208 00209 // Should potentially free cells be filtered? 00210 node_handle.param("ocmap_filter_outdated", m_bRemoveOutdated, m_bRemoveOutdated ); 00211 00212 // Should be the input cloud used for raycast filtering? 00213 node_handle.param("use_input_for_filter", m_bFilterWithInput, m_bFilterWithInput ); 00214 00215 // Octomap publishing topic 00216 node_handle.param("ocmap_publishing_topic", m_ocPublisherName, 00217 OCTOMAP_PUBLISHER_NAME); 00218 00219 // Advertise services 00220 m_serviceResetOctomap = node_handle.advertiseService(ResetOctomap_SRV, 00221 &srs_env_model::COctoMapPlugin::resetOctomapCB, this); 00222 00223 m_serviceRemoveCube = node_handle.advertiseService(RemoveCubeOctomap_SRV, 00224 &srs_env_model::COctoMapPlugin::removeCubeCB, this); 00225 00226 m_serviceAddCube = node_handle.advertiseService( AddCubeOctomap_SRV, 00227 &srs_env_model::COctoMapPlugin::addCubeCB, this); 00228 00229 m_serviceSetCrawlDepth = node_handle.advertiseService( SetCrawlDepth_SRV, 00230 &srs_env_model::COctoMapPlugin::setCrawlingDepthCB, this ); 00231 00232 m_serviceGetTreeDepth = node_handle.advertiseService( GetTreeDepth_SRV, 00233 &srs_env_model::COctoMapPlugin::getTreeDepthCB, this ); 00234 00235 m_serviceLoadMap = node_handle.advertiseService( LoadMap_SRV, 00236 &srs_env_model::COctoMapPlugin::loadOctreeCB, this); 00237 00238 m_serviceSaveMap = node_handle.advertiseService( SaveMap_SRV, 00239 &srs_env_model::COctoMapPlugin::saveOctreeCB, this); 00240 00241 m_serviceLoadFullMap = node_handle.advertiseService( LoadFullMap_SRV, 00242 &srs_env_model::COctoMapPlugin::loadFullOctreeCB, this); 00243 00244 m_serviceSaveFullMap = node_handle.advertiseService( SaveFullMap_SRV, 00245 &srs_env_model::COctoMapPlugin::saveFullOctreeCB, this); 00246 00247 00248 // Create publisher 00249 m_ocPublisher = node_handle.advertise<octomap_ros::OctomapBinary> ( 00250 m_ocPublisherName, 5, m_latchedTopics); 00251 00252 m_registration.init( node_handle ); 00253 00254 PERROR( "OctoMapPlugin initialized..." ); 00255 00256 m_bNotFirst = false; 00257 00258 m_probDeleted = m_mapParameters.probMiss * 0.1; 00259 00260 // Initialize filters 00261 m_filterSingleSpecles.setTreeFrameId(m_mapParameters.frameId); 00262 m_filterRaycast.setTreeFrameId(m_mapParameters.frameId); 00263 m_filterRaycast.init(node_handle); 00264 m_filterGround.setTreeFrameId(m_mapParameters.frameId); 00265 m_filterGround.init(node_handle); 00266 00267 // Set specles filter 20 seconds delay 00268 m_filterSingleSpecles.setRunMode( COcTreeFilterBase::FILTER_TEST_TIME ); 00269 m_filterSingleSpecles.setTimerLap(20); 00270 00271 // Create and connect filter cloud plugin, is needed 00272 if(!m_bFilterWithInput) 00273 { 00274 // Initialize filter pointcloud plugin 00275 std::cerr << "Initializing filter-in pointcloud plugin." << std::endl; 00276 m_filterCloudPlugin->init(node_handle, SUBSCRIBER_FILTERING_CLOUD_NAME); 00277 00278 // Disable cloud publishing 00279 m_filterCloudPlugin->enable(false); 00280 00281 // Connect input point cloud input with octomap 00282 m_filterCloudPlugin->getSigDataChanged().connect( boost::bind( &COctoMapPlugin::filterCloud, this, _1 )); 00283 } 00284 } 00285 00286 void srs_env_model::COctoMapPlugin::insertCloud(tPointCloud::ConstPtr cloud) 00287 { 00288 // PERROR("insertCloud: Try lock."); 00289 00290 // Lock data 00291 boost::mutex::scoped_lock lock(m_lockData); 00292 // PERROR("insertCloud: Locked."); 00293 00294 tPointCloud used_cloud; 00295 pcl::copyPointCloud( *cloud, used_cloud ); 00296 //* 00297 00298 Eigen::Matrix4f registration_transform( Eigen::Matrix4f::Identity() ); 00299 00300 // Registration 00301 { 00302 if( m_registration.isRegistering() && cloud->size() > 0 && m_bNotFirst ) 00303 { 00304 // pcl::copyPointCloud( *m_data, *m_bufferCloud ); 00305 00306 tPointCloudPtr cloudPtr( new tPointCloud ); 00307 pcl::copyPointCloud( *cloud, *cloudPtr ); 00308 00309 if( m_registration.registerCloud( cloudPtr, m_mapParameters ) ) 00310 { 00311 // std::cerr << "Starting registration process " << std::endl; 00312 00313 registration_transform = m_registration.getTransform(); 00314 00315 // pcl::transformPointCloud( cloud, used_cloud, transform ); 00316 00317 // std::cerr << "Registration succeeded" << std::endl; 00318 } 00319 else 00320 { 00321 // std::cerr << "reg failed." << std::endl; 00322 return; 00323 } 00324 } 00325 } 00326 00327 // ros::WallTime startTime = ros::WallTime::now(); 00328 00329 tPointCloud pc_ground; // segmented ground plane 00330 tPointCloud pc_nonground; // everything else 00331 00332 if (m_filterGroundPlane) 00333 { 00334 m_filterGround.setCloud(&used_cloud); 00335 m_filterGround.filter(m_data->getTree()); 00336 pc_ground = *m_filterGround.getGroundPc(); 00337 pc_nonground = *m_filterGround.getNongroundPc(); 00338 // m_filterGround.writeLastRunInfo(); 00339 00340 } else { 00341 pc_nonground = used_cloud; 00342 pc_ground.clear(); 00343 pc_ground.header = used_cloud.header; 00344 pc_nonground.header = used_cloud.header; 00345 } 00346 00347 tf::StampedTransform cloudToMapTf; 00348 00349 // PERROR("Get transforms."); 00350 00351 // Get transforms 00352 try { 00353 // Transformation - to, from, time, waiting time 00354 m_tfListener.waitForTransform(m_mapParameters.frameId, 00355 cloud->header.frame_id, cloud->header.stamp, ros::Duration(5)); 00356 00357 m_tfListener.lookupTransform(m_mapParameters.frameId, 00358 cloud->header.frame_id, cloud->header.stamp, cloudToMapTf); 00359 00360 } catch (tf::TransformException& ex) { 00361 ROS_ERROR_STREAM("Transform error: " << ex.what() << ", quitting callback"); 00362 PERROR( "Transform error."); 00363 return; 00364 } 00365 00366 // transform clouds to world frame for insertion 00367 if (m_mapParameters.frameId != cloud->header.frame_id) 00368 { 00369 Eigen::Matrix4f c2mTM; 00370 00371 // PERROR("Transforming."); 00372 00373 pcl_ros::transformAsMatrix(cloudToMapTf, c2mTM); 00374 pcl::transformPointCloud(pc_ground, pc_ground, c2mTM); 00375 pcl::transformPointCloud(pc_nonground, pc_nonground, c2mTM); 00376 } 00377 00378 // Use registration transform 00379 pcl::transformPointCloud( pc_ground, pc_ground, registration_transform ); 00380 00381 pc_ground.header = cloud->header; 00382 pc_ground.header.frame_id = m_mapParameters.frameId; 00383 00384 pc_nonground.header = cloud->header; 00385 pc_nonground.header.frame_id = m_mapParameters.frameId; 00386 00387 // 2012/12/14: Majkl (trying to solve problem with missing time stamps in all message headers) 00388 m_DataTimeStamp = cloud->header.stamp; 00389 ROS_DEBUG("COctoMapPlugin::insertCloud(): Stamp = %f", cloud->header.stamp.toSec()); 00390 00391 insertScan(cloudToMapTf.getOrigin(), pc_ground, pc_nonground); 00392 00393 if (m_removeSpecles) 00394 { 00395 //degradeSingleSpeckles(); 00396 m_filterSingleSpecles.filter(m_data->getTree()); 00397 m_filterSingleSpecles.writeLastRunInfo(); 00398 } 00399 00400 // PERROR("Outdated"); 00401 if (m_bRemoveOutdated && m_bFilterWithInput) 00402 { 00403 // std::cerr << "Raycast filter call" << std::endl; 00404 00405 // m_filterRaycast.setCloud(&cloud); 00406 // m_filterRaycast.filter(m_data->getTree()); 00407 // m_filterRaycast.writeLastRunInfo(); 00408 00409 // std::cerr << "Raycast filter call complete" << std::endl; 00410 } 00411 else 00412 m_bNewDataToFilter = true; 00413 00414 // double total_elapsed = (ros::WallTime::now() - startTime).toSec(); 00415 ROS_DEBUG("Point cloud insertion in OctomapServer done (%zu+%zu pts (ground/nonground).)", pc_ground.size(), 00416 pc_nonground.size()); 00417 00418 // PERROR("Filtered"); 00419 if (m_removeTester != 0) { 00420 long removed = doObjectTesting(m_removeTester); 00421 00422 PERROR( "Removed leafs: " << removed); 00423 00424 if (removed > 0) 00425 m_data->getTree().prune(); 00426 00427 --m_testerLifeCounter; 00428 00429 if (m_testerLifeCounter <= 0) { 00430 delete m_removeTester; 00431 m_removeTester = 0; 00432 } 00433 } 00434 00435 // Release lock 00436 lock.unlock(); 00437 00438 // PERROR("insertCloud: Unlocked."); 00439 00440 m_bNotFirst = true; 00441 00442 // Publish new data 00443 invalidate(); 00444 00445 // PERROR("insertCloud: End"); 00446 } 00447 00451 void srs_env_model::COctoMapPlugin::insertScan(const tf::Point & sensorOriginTf, 00452 const tPointCloud & ground, 00453 const tPointCloud & nonground) 00454 { 00455 octomap::point3d sensorOrigin = octomap::pointTfToOctomap(sensorOriginTf); 00456 00457 double maxRange(m_mapParameters.maxRange); 00458 /* 00459 octomap::Pointcloud pcNonground; 00460 octomap::pointcloudPCLToOctomap( nonground, pcNonground ); 00461 m_data->getTree().insertScan( pcNonground, sensorOrigin, maxRange, true, false ); 00462 */ 00463 m_data->getTree().insertColoredScan(nonground, sensorOrigin, maxRange, true); 00464 } 00465 00466 void srs_env_model::COctoMapPlugin::reset(bool clearLoaded) 00467 { 00468 if( m_bMapLoaded && (!clearLoaded) ) 00469 return; 00470 00471 // Lock data 00472 boost::mutex::scoped_lock lock(m_lockData); 00473 m_data->getTree().clear(); 00474 setDefaults(); 00475 } 00476 00480 void srs_env_model::COctoMapPlugin::filterCloud( tPointCloudConstPtr & cloud) 00481 { 00482 // std::cerr << "Filter cloud in" << std::endl; 00483 00484 if (m_bNewDataToFilter && m_bRemoveOutdated && (!m_bFilterWithInput)) 00485 { 00486 // Lock data 00487 boost::mutex::scoped_lock lock(m_lockData); 00488 00489 // std::cerr << "Raycast filter call" << std::endl; 00490 00491 m_filterRaycast.setCloud(cloud); 00492 m_filterRaycast.filter(m_data->getTree()); 00493 m_filterRaycast.writeLastRunInfo(); 00494 00495 // std::cerr << "Raycast filter call complete" << std::endl; 00496 } 00497 } 00498 00500 // OCTOMAP CRAWLING 00502 00504 void srs_env_model::COctoMapPlugin::crawl(const ros::Time & currentTime) 00505 { 00506 // Fill needed structures 00507 fillMapParameters(currentTime); 00508 00509 // Call new data signal 00510 m_sigOnNewData( m_mapParameters ); 00511 00512 } 00513 00515 bool srs_env_model::COctoMapPlugin::shouldPublish() 00516 { 00517 return (m_bPublishOctomap && m_ocPublisher.getNumSubscribers() > 0); 00518 } 00519 00523 void srs_env_model::COctoMapPlugin::publishInternal(const ros::Time & timestamp) 00524 { 00525 if( !shouldPublish() ) 00526 return; 00527 00528 // Lock data 00529 // PERROR( "publish: Try lock"); 00530 boost::mutex::scoped_lock lock(m_lockData); 00531 // PERROR( "publish: Locked"); 00532 00533 octomap_ros::OctomapBinary map; 00534 map.header.frame_id = m_mapParameters.frameId; 00535 map.header.stamp = timestamp; 00536 00537 octomap::octomapMapToMsgData(m_data->getTree(), map.data); 00538 00539 m_ocPublisher.publish(map); 00540 00541 // PERROR( "publish: Unlocked"); 00542 } 00543 00545 void srs_env_model::COctoMapPlugin::fillMapParameters(const ros::Time & time) 00546 { 00547 m_mapParameters.currentTime = time; 00548 m_mapParameters.mapSize = m_data->getTree().size(); 00549 m_mapParameters.treeDepth = m_data->getTree().getTreeDepth(); 00550 } 00551 00553 00558 bool srs_env_model::COctoMapPlugin::resetOctomapCB(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) 00559 { 00560 std::cerr << "Reset octomap service called..." << std::endl; 00561 00562 // When reseting, loaded octomap should be cleared 00563 reset(true); 00564 00565 std::cerr << "Reset done..." << std::endl; 00566 00567 invalidate(); 00568 00569 return true; 00570 } 00571 00572 // ============================================================================ 00573 // Filtering 00574 00578 long int srs_env_model::COctoMapPlugin::doObjectTesting(srs_env_model::CTestingObjectBase * object) 00579 { 00580 if (object == 0) { 00581 PERROR( "Wrong testing object - NULL. "); 00582 return 0; 00583 } 00584 00585 // Create removed nodes counter 00586 long int counter(0); 00587 00588 float probMiss(m_data->getTree().getProbMissLog()); 00589 00590 // For all leafs 00591 for (srs_env_model::tButServerOcTree::leaf_iterator it = 00592 m_data->getTree().begin_leafs(), end = m_data->getTree().end_leafs(); it 00593 != end; ++it) { 00594 // Node is occupied? 00595 if (m_data->getTree().isNodeOccupied(*it)) 00596 { 00597 // Node is in testing object 00598 if (object->isIn(it.getX(), it.getY(), it.getZ())) { 00599 // "Remove" node 00600 // m_data->getTree().setNodeColor(it.getKey(), 255, 0, 0, 255); 00601 (*it).setValue(probMiss); 00602 // m_data->getTree().updateNodeLogOdds(&*it, -0.8); 00603 ++counter; 00604 } 00605 00606 } 00607 } 00608 00609 return counter; 00610 } 00614 #define G2EPOINT( gp ) (Eigen::Vector3f( gp.x, gp.y, gp.z )) 00615 //#define G2EQUAT( gp ) (Eigen::Quaternionf( gp.x, gp.y, gp.z, gp.w )) 00616 #define G2EQUAT( gp ) (Eigen::Quaternionf( gp.w, gp.x, gp.y, gp.z )) 00617 bool srs_env_model::COctoMapPlugin::removeCubeCB( 00618 srs_env_model::RemoveCube::Request & req, 00619 srs_env_model::RemoveCube::Response & res) { 00620 00621 PERROR( "Remove cube from octomap: " << req.pose << " --- " << req.size ); 00622 00623 // Debug - show cube position 00624 //addCubeGizmo( req.pose, req.size ); 00625 00626 if (m_removeTester != 0) 00627 delete m_removeTester; 00628 00629 // Test frame id 00630 if (req.frame_id != m_mapParameters.frameId) { 00631 // Transform pose 00632 geometry_msgs::PoseStamped ps, psout; 00633 ps.header.frame_id = req.frame_id; 00634 ps.header.stamp = m_mapParameters.currentTime; 00635 ps.pose = req.pose; 00636 00637 m_tfListener.transformPose(m_mapParameters.frameId, ps, psout); 00638 req.pose = psout.pose; 00639 00640 // Transform size 00641 geometry_msgs::PointStamped vs, vsout; 00642 vs.header.frame_id = req.frame_id; 00643 vs.header.stamp = m_mapParameters.currentTime; 00644 vs.point = req.size; 00645 00646 m_tfListener.transformPoint(m_mapParameters.frameId, vs, vsout); 00647 req.size = vsout.point; 00648 00649 PERROR( "Transformed cube from octomap: " << req.pose << " --- " << req.size ); 00650 } 00651 00652 // Add bit of size 00653 double d(m_mapParameters.resolution); 00654 00655 // Create new tester 00656 m_removeTester = new srs_env_model::CTestingPolymesh( 00657 G2EPOINT( req.pose.position ), G2EQUAT( req.pose.orientation ), 00658 G2EPOINT( req.size ) + Eigen::Vector3f(d, d, d)); 00659 00660 // Set it to life 00661 m_testerLifeCounter = m_testerLife; 00662 00663 return true; 00664 } 00665 00666 bool srs_env_model::COctoMapPlugin::addCubeCB( 00667 srs_env_model::AddCube::Request & req, 00668 srs_env_model::AddCube::Response & res) { 00669 00670 PERROR( "Add cube to octomap: " << req.pose << " --- \n size: \n" << req.size ); 00671 00672 // Debug - show cube position 00673 //addCubeGizmo( req.pose, req.size ); 00674 00675 // Test frame id 00676 if (req.frame_id != m_mapParameters.frameId) { 00677 // Transform pose 00678 geometry_msgs::PoseStamped ps, psout; 00679 ps.header.frame_id = req.frame_id; 00680 ps.header.stamp = m_mapParameters.currentTime; 00681 ps.pose = req.pose; 00682 00683 m_tfListener.transformPose(m_mapParameters.frameId, ps, psout); 00684 req.pose = psout.pose; 00685 00686 // Transform size 00687 geometry_msgs::PointStamped vs, vsout; 00688 vs.header.frame_id = req.frame_id; 00689 vs.header.stamp = m_mapParameters.currentTime; 00690 vs.point = req.size; 00691 00692 m_tfListener.transformPoint(m_mapParameters.frameId, vs, vsout); 00693 req.size = vsout.point; 00694 00695 // PERROR( "Transformed cube from octomap: " << req.pose << " --- " << req.size ); 00696 } 00697 00698 PERROR( "Computing sizes..." ); 00699 00700 // Compute minimal and maximal value 00701 octomap::point3d pmin, pmax; 00702 pmin(0) = req.pose.position.x - req.size.x * 0.5; 00703 pmin(1) = req.pose.position.y - req.size.y * 0.5; 00704 pmin(2) = req.pose.position.z - req.size.z * 0.5; 00705 00706 pmax(0) = req.pose.position.x + req.size.x * 0.5; 00707 pmax(1) = req.pose.position.y + req.size.y * 0.5; 00708 pmax(2) = req.pose.position.z + req.size.z * 0.5; 00709 00710 PERROR( "Sizes computed. Computing steps "); 00711 00712 float diff[3]; 00713 unsigned int steps[3]; 00714 for (int i=0;i<3;++i) 00715 { 00716 diff[i] = pmax(i) - pmin(i); 00717 steps[i] = floor(diff[i] / m_mapParameters.resolution); 00718 00719 std::cerr << "bbx " << i << " size: " << diff[i] << " " << steps[i] << " steps\n"; 00720 } 00721 00722 PERROR("Rendering... Resolution: " << m_mapParameters.resolution ); 00723 00724 long counter(0); 00725 octomap::point3d p = pmin; 00726 octomap::OcTreeKey key; 00727 00728 for (unsigned int x = 0; x < steps[0]; ++x) 00729 { 00730 p.x() += m_mapParameters.resolution; 00731 p.y() = pmin.y(); 00732 00733 for (unsigned int y = 0; y < steps[1]; ++y) 00734 { 00735 p.y() += m_mapParameters.resolution; 00736 p.z() = pmin.z(); 00737 00738 for (unsigned int z = 0; z < steps[2]; ++z) 00739 { 00740 // std::cout << "querying p=" << p << std::endl; 00741 p.z() += m_mapParameters.resolution; 00742 ++counter; 00743 00744 // Try to generate octree key 00745 if (!m_data->getTree().genKey(p, key)) continue; 00746 00747 // Set node value 00748 m_data->getTree().updateNode(key, true, true); 00749 // Set node color 00750 m_data->getTree().setNodeColor(key, m_r, m_g, m_b, 255); 00751 } 00752 } 00753 } 00754 00755 PERROR( "Added. Changed nodes: " << counter ); 00756 return true; 00757 } 00758 00762 void srs_env_model::COctoMapPlugin::addCubeGizmo( 00763 const geometry_msgs::Pose & pose, const geometry_msgs::Point & size) { 00764 srs_interaction_primitives::AddUnknownObject gizmo; 00765 gizmo.request.pose = pose; 00766 gizmo.request.scale.x = size.x; 00767 gizmo.request.scale.y = size.y; 00768 gizmo.request.scale.z = size.z; 00769 gizmo.request.frame_id = m_mapParameters.frameId; 00770 gizmo.request.name = "OctomapGizmo"; 00771 00772 ros::service::call("but_interaction_primitives/add_unknown_object", gizmo); 00773 } 00774 00778 void srs_env_model::COctoMapPlugin::pause( bool bPause, ros::NodeHandle & node_handle ) 00779 { 00780 boost::mutex::scoped_lock lock(m_lockData); 00781 00782 if( bPause ) 00783 { 00784 m_ocPublisher.shutdown(); 00785 // m_ciSubscriber.shutdown(); 00786 // m_markerPublisher.shutdown(); 00787 } 00788 else 00789 { 00790 m_ocPublisher = node_handle.advertise<octomap_ros::OctomapBinary> ( m_ocPublisherName, 5, m_latchedTopics); 00791 00792 // Add camera info subscriber 00793 // m_ciSubscriber = node_handle.subscribe(m_camera_info_topic, 10, &srs_env_model::COctoMapPlugin::cameraInfoCB, this); 00794 00795 // If should publish, create markers publisher 00796 // m_markerPublisher = node_handle.advertise<visualization_msgs::Marker> ( m_markers_topic_name, 10); 00797 } 00798 } 00799 00803 bool srs_env_model::COctoMapPlugin::setCrawlingDepthCB( srs_env_model::SetCrawlingDepth::Request & req, srs_env_model::SetCrawlingDepth::Response & res ) 00804 { 00805 boost::mutex::scoped_lock lock(m_lockData); 00806 m_crawlDepth = req.depth; 00807 00808 // Test maximal value 00809 unsigned char td( m_data->getTree().getTreeDepth() ); 00810 if( m_crawlDepth > td) 00811 m_crawlDepth = td; 00812 00813 m_mapParameters.crawlDepth = m_crawlDepth; 00814 00815 return true; 00816 } 00817 00821 bool srs_env_model::COctoMapPlugin::getTreeDepthCB( srs_env_model::GetTreeDepth::Request & req, srs_env_model::GetTreeDepth::Response & res ) 00822 { 00823 res.depth = m_data->getTree().getTreeDepth(); 00824 00825 return true; 00826 } 00827 00831 bool srs_env_model::COctoMapPlugin::loadOctreeCB( srs_env_model::LoadSaveRequest & req, srs_env_model::LoadSaveResponse & res ) 00832 { 00833 // reset data 00834 reset(true); 00835 00836 boost::mutex::scoped_lock lock(m_lockData); 00837 00838 setDefaults(); 00839 00840 assert( m_data != 0 ); 00841 00842 // Set octomap parameters 00843 m_data->getTree().setProbHit(m_mapParameters.probHit); 00844 m_data->getTree().setProbMiss(m_mapParameters.probMiss); 00845 m_data->getTree().setClampingThresMin(m_mapParameters.thresMin); 00846 m_data->getTree().setClampingThresMax(m_mapParameters.thresMax); 00847 m_data->getTree().setOccupancyThres(m_mapParameters.thresOccupancy); 00848 m_mapParameters.treeDepth = m_data->getTree().getTreeDepth(); 00849 m_mapParameters.map = m_data; 00850 m_mapParameters.crawlDepth = m_crawlDepth; 00851 00852 // is filename valid? 00853 if (req.filename.length() > 0) { 00854 // Try to load data 00855 if (m_data->getTree().readBinary(req.filename)) { 00856 ROS_INFO("Octomap file %s loaded (%zu nodes).", req.filename.c_str(), m_data->getTree().size()); 00857 00858 // get tree depth 00859 m_mapParameters.treeDepth = m_data->getTree().getTreeDepth(); 00860 00861 // get resolution 00862 m_mapParameters.resolution = m_data->getTree().getResolution(); 00863 00864 // Map was loaded 00865 m_bMapLoaded = true; 00866 00867 // Unlock data before invalidation 00868 lock.unlock(); 00869 00870 // We have new data 00871 invalidate(); 00872 00873 res.all_ok = true; 00874 00875 m_bNotFirst = m_data->getTree().getNumLeafNodes() > 0; 00876 00877 } else { 00878 00879 // Something is wrong - cannot load data... 00880 ROS_ERROR("Could not open requested file %s, continuing in standard mode.", req.filename.c_str()); 00881 PERROR( "Transform error."); 00882 00883 res.all_ok = false; 00884 } 00885 } 00886 00887 return true; 00888 } 00889 00893 bool srs_env_model::COctoMapPlugin::saveOctreeCB( srs_env_model::LoadSaveRequest & req, srs_env_model::LoadSaveResponse & res ) 00894 { 00895 if(req.filename.length() == 0 ) 00896 { 00897 ROS_ERROR("Wrong filename: Zero length string."); 00898 res.all_ok = false; 00899 return false; 00900 } 00901 00902 bool rv(m_data->getTree().writeBinaryConst(req.filename)); 00903 00904 if( !rv ) 00905 { 00906 ROS_ERROR("Could not save file: %s", req.filename.c_str()); 00907 res.all_ok = false; 00908 return false; 00909 } 00910 00911 res.all_ok = true; 00912 return true; 00913 } 00914 00918 bool srs_env_model::COctoMapPlugin::loadFullOctreeCB( srs_env_model::LoadSaveRequest & req, srs_env_model::LoadSaveResponse & res ) 00919 { 00920 // reset data 00921 reset(true); 00922 00923 boost::mutex::scoped_lock lock(m_lockData); 00924 00925 setDefaults(); 00926 00927 assert( m_data != 0 ); 00928 00929 // Set octomap parameters 00930 m_data->getTree().setProbHit(m_mapParameters.probHit); 00931 m_data->getTree().setProbMiss(m_mapParameters.probMiss); 00932 m_data->getTree().setClampingThresMin(m_mapParameters.thresMin); 00933 m_data->getTree().setClampingThresMax(m_mapParameters.thresMax); 00934 m_data->getTree().setOccupancyThres(m_mapParameters.thresOccupancy); 00935 m_mapParameters.treeDepth = m_data->getTree().getTreeDepth(); 00936 m_mapParameters.map = m_data; 00937 m_mapParameters.crawlDepth = m_crawlDepth; 00938 00939 // is filename valid? 00940 if (req.filename.length() > 0) { 00941 // Try to load data 00942 srs_env_model::tButServerOcTree * tree = dynamic_cast<tButServerOcTree *>( tButServerOcTree::read( req.filename ) ); 00943 if (tree != 0 ) 00944 { 00945 // Remove old, create new 00946 m_data->setTree( tree ); 00947 tree->prune(); 00948 00949 ROS_INFO("Octomap file %s loaded (%zu nodes).", req.filename.c_str(), m_data->getTree().size()); 00950 00951 // get tree depth 00952 m_mapParameters.treeDepth = tree->getTreeDepth(); 00953 00954 // get resolution 00955 m_mapParameters.resolution = tree->getResolution(); 00956 00957 // Get hit probability 00958 m_mapParameters.probHit = tree->getProbHit(); 00959 00960 // Get miss probability 00961 m_mapParameters.probMiss = tree->getProbMiss(); 00962 00963 // Clamping minimum threshold 00964 m_mapParameters.thresMin = tree->getClampingThresMin(); 00965 00966 // Clamping threshold maximum 00967 m_mapParameters.thresMax = tree->getClampingThresMax(); 00968 00969 // Occupancy threshold 00970 m_mapParameters.thresOccupancy = tree->getOccupancyThres(); 00971 00972 00973 // Map was loaded 00974 m_bMapLoaded = true; 00975 00976 // Unlock data before invalidation 00977 lock.unlock(); 00978 00979 // We have new data 00980 invalidate(); 00981 00982 res.all_ok = true; 00983 00984 m_bNotFirst = m_data->getTree().getNumLeafNodes() > 0; 00985 00986 } else { 00987 00988 // Something is wrong - cannot load data... 00989 ROS_ERROR("Could not open requested file %s, continuing in standard mode.", req.filename.c_str()); 00990 PERROR( "Transform error."); 00991 00992 res.all_ok = false; 00993 } 00994 } 00995 00996 return true; 00997 } 00998 01002 bool srs_env_model::COctoMapPlugin::saveFullOctreeCB( srs_env_model::LoadSaveRequest & req, srs_env_model::LoadSaveResponse & res ) 01003 { 01004 if(req.filename.length() == 0 ) 01005 { 01006 ROS_ERROR("Wrong filename: Zero length string."); 01007 res.all_ok = false; 01008 return false; 01009 } 01010 01011 bool rv(m_data->getTree().write(req.filename)); 01012 01013 if( !rv ) 01014 { 01015 ROS_ERROR("Could not save file: %s", req.filename.c_str()); 01016 res.all_ok = false; 01017 return false; 01018 } 01019 01020 res.all_ok = true; 01021 return true; 01022 }