$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 #pragma once 00028 #ifndef OCTOMAPPLUGIN_H_INCLUDED 00029 #define OCTOMAPPLUGIN_H_INCLUDED 00030 00031 #include <srs_env_model/but_server/server_tools.h> 00032 #include <srs_env_model/but_server/plugins/octomap_plugin_tools/testing_oriented_box.h> 00033 #include <srs_env_model/but_server/plugins/octomap_plugin_tools/testing_sphere.h> 00034 #include <srs_env_model/but_server/plugins/octomap_plugin_tools/testing_polymesh.h> 00035 00036 #include <tf/transform_listener.h> 00037 #include <std_srvs/Empty.h> 00038 00039 #include <srs_env_model/RemoveCube.h> 00040 #include <srs_env_model/AddCube.h> 00041 #include <srs_env_model/SetCrawlingDepth.h> 00042 #include <srs_env_model/GetTreeDepth.h> 00043 00044 #include <srs_env_model/LoadSave.h> 00045 00046 // Registration 00047 #include <srs_env_model/but_server/registration/CPCtoOCRegistration.h> 00048 00049 #include "octomap_plugin_tools/octomap_filter_single_specles.h" 00050 #include "octomap_plugin_tools/octomap_filter_raycast.h" 00051 #include "octomap_plugin_tools/octomap_filter_ground.h" 00052 00053 //======================== 00054 // Filtering 00055 00056 #include <image_geometry/pinhole_camera_model.h> 00057 00058 namespace srs_env_model 00059 { 00063 class CPointCloudPlugin; 00064 00068 class COctoMapPlugin : public CServerPluginBase, public CDataHolderBase< tButServerOcMap > 00069 { 00070 public: 00072 typedef boost::signal< void (SMapWithParameters &) > tSigOnNewData; 00073 00074 public: 00076 COctoMapPlugin(const std::string & name); 00077 00079 COctoMapPlugin( const std::string & name, const std::string & filename ); 00080 00082 virtual ~COctoMapPlugin(); 00083 00085 void insertCloud(tPointCloud::ConstPtr cloud); 00086 00088 virtual void init(ros::NodeHandle & node_handle); 00089 00091 void reset(bool clearLoaded = true); 00092 00094 unsigned getSize() { return m_data->getTree().size(); } 00095 00097 unsigned getTreeDepth() { return m_mapParameters.treeDepth; } 00098 00100 double getResolution(){ return m_mapParameters.resolution; } 00101 00103 void crawl( const ros::Time & currentTime ); 00104 00105 tSigOnNewData & getSigOnNewData() { return m_sigOnNewData; } 00106 00108 virtual void pause( bool bPause, ros::NodeHandle & node_handle ); 00109 00110 protected: 00112 virtual bool shouldPublish(); 00113 00115 virtual void publishInternal(const ros::Time & timestamp); 00116 00118 void setDefaults(); 00119 00123 void insertScan(const tf::Point& sensorOriginTf, const tPointCloud& ground, const tPointCloud& nonground); 00124 00126 void fillMapParameters(const ros::Time & time); 00127 00129 bool resetOctomapCB(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response); 00130 00132 void filterCloud( tPointCloudConstPtr & cloud); 00133 00134 00135 // ------------------------------------------------------------------------ 00136 // Obstacle cleaning 00137 00139 long int doObjectTesting( CTestingObjectBase * object ); 00140 00142 bool removeCubeCB( srs_env_model::RemoveCube::Request & req, srs_env_model::RemoveCube::Response & res ); 00143 00145 bool addCubeCB( srs_env_model::AddCube::Request & req, srs_env_model::AddCube::Response & res ); 00146 00148 void addCubeGizmo( const geometry_msgs::Pose & pose, const geometry_msgs::Point & size ); 00149 00151 bool setCrawlingDepthCB( srs_env_model::SetCrawlingDepth::Request & req, srs_env_model::SetCrawlingDepth::Response & res ); 00152 00154 bool getTreeDepthCB( srs_env_model::GetTreeDepth::Request & req, srs_env_model::GetTreeDepth::Response & res ); 00155 00157 bool loadOctreeCB( srs_env_model::LoadSaveRequest & req, srs_env_model::LoadSaveResponse & res ); 00158 00160 bool saveOctreeCB( srs_env_model::LoadSaveRequest & req, srs_env_model::LoadSaveResponse & res ); 00161 00163 bool loadFullOctreeCB( srs_env_model::LoadSaveRequest & req, srs_env_model::LoadSaveResponse & res ); 00164 00166 bool saveFullOctreeCB( srs_env_model::LoadSaveRequest & req, srs_env_model::LoadSaveResponse & res ); 00167 00168 00169 protected: 00170 00172 bool m_filterGroundPlane; 00173 00175 octomap::KeyRay m_keyRay; 00176 00178 tSigOnNewData m_sigOnNewData; 00179 00181 SMapWithParameters m_mapParameters; 00182 00184 tf::TransformListener m_tfListener; 00185 00187 ros::ServiceServer m_serviceResetOctomap; 00188 00190 ros::ServiceServer m_serviceRemoveCube; 00191 00193 ros::ServiceServer m_serviceAddCube; 00194 00196 ros::ServiceServer m_serviceSetCrawlDepth; 00197 00199 ros::ServiceServer m_serviceGetTreeDepth; 00200 00202 ros::ServiceServer m_serviceLoadMap; 00203 00205 ros::ServiceServer m_serviceSaveMap; 00206 00208 ros::ServiceServer m_serviceLoadFullMap; 00209 00211 ros::ServiceServer m_serviceSaveFullMap; 00212 00214 bool m_bPublishOctomap; 00215 00217 std::string m_ocPublisherName; 00218 00220 ros::Publisher m_ocPublisher; 00221 00222 bool m_latchedTopics; 00223 00225 bool m_removeSpecles; 00226 00227 int filecounter; 00228 00229 //========================================================================= 00230 // Filtering 00231 00232 COcFilterSingleSpecles m_filterSingleSpecles; 00233 COcFilterRaycast m_filterRaycast; 00234 COcFilterGround m_filterGround; 00235 00237 bool m_bFilterWithInput; 00238 00240 boost::shared_ptr< CPointCloudPlugin > m_filterCloudPlugin; 00241 00243 bool m_bRemoveOutdated; 00244 00246 bool m_bNewDataToFilter; 00247 00249 CTestingObjectBase * m_removeTester; 00250 00252 unsigned int m_testerLife; 00253 00255 unsigned int m_testerLifeCounter; 00256 00258 unsigned char m_crawlDepth; 00259 00261 CPcToOcRegistration m_registration; 00262 00264 bool m_bNotFirst; 00265 00267 bool m_bMapLoaded; 00268 00270 float m_probDeleted; 00271 00273 uint8_t m_r, m_g, m_b; 00274 00275 00276 }; // class COctoMapPlugin; 00277 00278 00279 } 00280 00281 00282 00283 // namespace srs_env_model 00284 00285 // OCTOMAPPLUGIN_H_INCLUDED 00286 #endif 00287