$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 SERVER_TOOLS_H_INCLUDED 00029 #define SERVER_TOOLS_H_INCLUDED 00030 00031 #include <srs_env_model/but_server/octonode.h> 00032 00033 #include <boost/signal.hpp> 00034 #include <boost/thread/mutex.hpp> 00035 #include <boost/make_shared.hpp> 00036 00037 // Small double number 00038 #define SMALL_DOUBLE double(0.00000001); 00039 00041 template <typename tpType> tpType abs( tpType x ) { return x < 0.0 ? -x : x; } 00042 00044 template <typename tpType> bool isSmall( tpType x ) { return abs( x ) < SMALL_DOUBLE; } 00045 00047 template <typename tpType> bool isGreat( tpType x ) { return abs( x ) > SMALL_DOUBLE; } 00048 00049 namespace srs_env_model 00050 { 00052 typedef octomap::ButOctomapROS< srs_env_model::EMOcTree > tButServerOcMap; 00053 00055 typedef boost::shared_ptr<tButServerOcMap> tButServerOcMapPtr; 00056 00058 typedef boost::shared_ptr< const tButServerOcMap > tButServerOcMapConstPtr; 00059 00061 typedef tButServerOcMap::OcTreeType tButServerOcTree; 00062 00064 typedef tButServerOcTree::NodeType tButServerOcNode; 00065 00067 typedef pcl::PointXYZRGB tPclPoint; 00068 00070 typedef pcl::PointCloud<tPclPoint> tPointCloud; 00071 00073 typedef tPointCloud::Ptr tPointCloudPtr; 00074 00076 typedef tPointCloud::ConstPtr tPointCloudConstPtr; 00077 00079 struct SMapWithParameters 00080 { 00081 public: 00083 double resolution; 00084 00086 unsigned treeDepth; 00087 00089 unsigned char crawlDepth; 00090 00092 double probHit; 00093 00095 double probMiss; 00096 00098 double thresMin; 00099 00101 double thresMax; 00102 00104 double thresOccupancy; 00105 00107 double maxRange; 00108 00110 unsigned mapSize; 00111 00113 ros::Time currentTime; 00114 00116 std::string frameId; 00117 00119 boost::shared_ptr<tButServerOcMap> map; 00120 00121 }; // struct SMapParameters. 00122 00124 00126 class CServerPluginBase 00127 { 00128 #define PERROR( x ) std::cerr << "Plugin "<< this->m_name << ": " << x << std::endl; 00129 00130 public: 00132 CServerPluginBase( const std::string & name ) 00133 : m_name(name) 00134 { } 00135 00137 virtual ~CServerPluginBase() {} 00138 00140 virtual void init(ros::NodeHandle & node_handle) 00141 { 00142 } 00143 00145 void publish(const ros::Time & timestamp) 00146 { 00147 if( shouldPublish() ) publishInternal( timestamp ); 00148 } 00149 00151 virtual void reset() {} 00152 00154 virtual void pause( bool bPause, ros::NodeHandle & node_handle ){} 00155 00157 std::string getName( ) { return m_name; } 00158 00159 00160 protected: 00162 virtual bool shouldPublish() = 0; 00163 00165 virtual void publishInternal( const ros::Time & timestamp ) = 0; 00166 00167 protected: 00169 std::string m_name; 00170 00172 boost::mutex m_lockMutex; 00173 }; 00174 00175 00177 template< class tpNodeType > 00178 class COctomapCrawlerBase 00179 { 00180 public: 00182 COctomapCrawlerBase() : m_crawlDepth(0) {} 00183 00185 virtual ~COctomapCrawlerBase() {} 00186 00188 void handleNewMapData( SMapWithParameters & par ) 00189 { 00190 if( wantsMap() ) newMapDataCB( par ); 00191 } 00192 00194 virtual bool wantsMap() { return true; } 00195 00196 protected: 00198 virtual void newMapDataCB( SMapWithParameters & par ) = 0; 00199 00200 protected: 00202 std::string m_frame_id; 00203 00205 ros::Time m_time_stamp; 00206 00208 unsigned char m_crawlDepth; 00209 }; 00210 00211 00215 template< class tpDataType > 00216 class CDataHolderBase 00217 { 00218 public: 00220 typedef tpDataType tData; 00221 00223 typedef boost::shared_ptr< tData > tDataPtr; 00224 00226 typedef boost::shared_ptr< const tData > tDataConstPtr; 00227 00229 typedef boost::signal< void (tDataConstPtr, const ros::Time & ) > tSigDataHasChanged; 00230 00232 // 2012/12/14 Majkl: Trying to solve problem with missing time stamps 00233 // CDataHolderBase() : m_data(new tData) {} 00234 // CDataHolderBase() : m_data(new tData), m_DataTimeStamp(ros::Time(0)) {} 00235 CDataHolderBase() : m_DataTimeStamp(ros::Time::now()) {m_data = boost::make_shared<tData>();} 00236 00238 // CDataHolderBase( tData * data ) : m_data(data) {} 00239 // CDataHolderBase( tData * data ) : m_data(data), m_DataTimeStamp(ros::Time(0)) {} 00240 CDataHolderBase( tData * data ) : m_data(data), m_DataTimeStamp(ros::Time::now()) {} 00241 00242 public: 00244 virtual ~CDataHolderBase() {} 00245 00247 tData & getData(){ return *m_data; } 00248 00250 const tData & getData() const { return *m_data; } 00251 00253 tSigDataHasChanged & getSigDataChanged() { return m_sigDataChanged; } 00254 00256 virtual bool hasValidData() { return m_data != 0; } 00257 00259 void invalidate() 00260 { 00261 if( hasValidData() ) 00262 { 00263 // std::cerr << "invalidate: Locked." << std::endl; 00264 boost::mutex::scoped_lock lock(m_lockData); 00265 m_sigDataChanged( m_data, m_DataTimeStamp ); 00266 // std::cerr << "invalidate: Unlocked." << std::endl; 00267 } 00268 } 00269 00270 protected: 00272 tDataPtr m_data; 00273 00275 ros::Time m_DataTimeStamp; 00276 00278 tSigDataHasChanged m_sigDataChanged; 00279 00281 boost::mutex m_lockData; 00282 }; 00283 00284 } // namespace srs_env_model 00285 00286 /* 00287 POINT_CLOUD_REGISTER_POINT_STRUCT(pcl::PointXYZRGB, 00288 (float, x, x) 00289 (float, y, y) 00290 (float, z, z) 00291 (uint32_t, rgb, rgb) 00292 ) 00293 */ 00294 // SERVER_TOOLS_H_INCLUDED 00295 #endif