OctomapServer.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010-2013, A. Hornung, University of Freiburg
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the University of Freiburg nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef OCTOMAP_SERVER_OCTOMAPSERVER_H
31 #define OCTOMAP_SERVER_OCTOMAPSERVER_H
32 
33 #include <ros/ros.h>
34 #include <visualization_msgs/MarkerArray.h>
35 #include <nav_msgs/OccupancyGrid.h>
36 #include <std_msgs/ColorRGBA.h>
37 
38 // #include <moveit_msgs/CollisionObject.h>
39 // #include <moveit_msgs/CollisionMap.h>
40 #include <sensor_msgs/PointCloud2.h>
41 #include <std_srvs/Empty.h>
42 #include <dynamic_reconfigure/server.h>
43 #include <octomap_server/OctomapServerConfig.h>
44 
45 #include <pcl/point_types.h>
46 #include <pcl/conversions.h>
47 #include <pcl_ros/transforms.h>
48 #include <pcl/sample_consensus/method_types.h>
49 
50 #pragma GCC diagnostic push
51 #pragma GCC diagnostic ignored "-Wdeprecated-declarations" // pcl::SAC_SAMPLE_SIZE is protected since PCL 1.8.0
52 #include <pcl/sample_consensus/model_types.h>
53 #pragma GCC diagnostic pop
54 
55 #include <pcl/segmentation/sac_segmentation.h>
56 #include <pcl/io/pcd_io.h>
57 #include <pcl/filters/extract_indices.h>
58 #include <pcl/filters/passthrough.h>
60 
61 
62 #include <tf/transform_listener.h>
63 #include <tf/message_filter.h>
65 #include <octomap_msgs/Octomap.h>
66 #include <octomap_msgs/GetOctomap.h>
67 #include <octomap_msgs/BoundingBoxQuery.h>
69 
71 #include <octomap/octomap.h>
72 #include <octomap/OcTreeKey.h>
73 
74 //#define COLOR_OCTOMAP_SERVER // switch color here - easier maintenance, only maintain OctomapServer. Two targets are defined in the cmake, octomap_server_color and octomap_server. One has this defined, and the other doesn't
75 
76 #ifdef COLOR_OCTOMAP_SERVER
77 #include <octomap/ColorOcTree.h>
78 #endif
79 
80 namespace octomap_server {
82 
83 public:
84 #ifdef COLOR_OCTOMAP_SERVER
85  typedef pcl::PointXYZRGB PCLPoint;
86  typedef pcl::PointCloud<pcl::PointXYZRGB> PCLPointCloud;
88 #else
89  typedef pcl::PointXYZ PCLPoint;
90  typedef pcl::PointCloud<pcl::PointXYZ> PCLPointCloud;
92 #endif
93  typedef octomap_msgs::GetOctomap OctomapSrv;
94  typedef octomap_msgs::BoundingBoxQuery BBXSrv;
95 
96  OctomapServer(const ros::NodeHandle private_nh_ = ros::NodeHandle("~"), const ros::NodeHandle &nh_ = ros::NodeHandle());
97  virtual ~OctomapServer();
98  virtual bool octomapBinarySrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res);
99  virtual bool octomapFullSrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res);
100  bool clearBBXSrv(BBXSrv::Request& req, BBXSrv::Response& resp);
101  bool resetSrv(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp);
102 
103  virtual void insertCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& cloud);
104  virtual bool openFile(const std::string& filename);
105 
106 protected:
107  inline static void updateMinKey(const octomap::OcTreeKey& in, octomap::OcTreeKey& min) {
108  for (unsigned i = 0; i < 3; ++i)
109  min[i] = std::min(in[i], min[i]);
110  };
111 
112  inline static void updateMaxKey(const octomap::OcTreeKey& in, octomap::OcTreeKey& max) {
113  for (unsigned i = 0; i < 3; ++i)
114  max[i] = std::max(in[i], max[i]);
115  };
116 
118  inline bool isInUpdateBBX(const OcTreeT::iterator& it) const {
119  // 2^(tree_depth-depth) voxels wide:
120  unsigned voxelWidth = (1 << (m_maxTreeDepth - it.getDepth()));
121  octomap::OcTreeKey key = it.getIndexKey(); // lower corner of voxel
122  return (key[0] + voxelWidth >= m_updateBBXMin[0]
123  && key[1] + voxelWidth >= m_updateBBXMin[1]
124  && key[0] <= m_updateBBXMax[0]
125  && key[1] <= m_updateBBXMax[1]);
126  }
127 
128  void reconfigureCallback(octomap_server::OctomapServerConfig& config, uint32_t level);
129  void publishBinaryOctoMap(const ros::Time& rostime = ros::Time::now()) const;
130  void publishFullOctoMap(const ros::Time& rostime = ros::Time::now()) const;
131  void publishProjected2DMap(const ros::Time& rostime = ros::Time::now());
132  virtual void publishAll(const ros::Time& rostime = ros::Time::now());
133 
142  virtual void insertScan(const tf::Point& sensorOrigin, const PCLPointCloud& ground, const PCLPointCloud& nonground);
143 
145  void filterGroundPlane(const PCLPointCloud& pc, PCLPointCloud& ground, PCLPointCloud& nonground) const;
146 
152  bool isSpeckleNode(const octomap::OcTreeKey& key) const;
153 
155  virtual void handlePreNodeTraversal(const ros::Time& rostime);
156 
158  virtual void handleNode(const OcTreeT::iterator& it) {};
159 
161  virtual void handleNodeInBBX(const OcTreeT::iterator& it) {};
162 
164  virtual void handleOccupiedNode(const OcTreeT::iterator& it);
165 
167  virtual void handleOccupiedNodeInBBX(const OcTreeT::iterator& it);
168 
170  virtual void handleFreeNode(const OcTreeT::iterator& it);
171 
173  virtual void handleFreeNodeInBBX(const OcTreeT::iterator& it);
174 
176  virtual void handlePostNodeTraversal(const ros::Time& rostime);
177 
179  virtual void update2DMap(const OcTreeT::iterator& it, bool occupied);
180 
181  inline unsigned mapIdx(int i, int j) const {
182  return m_gridmap.info.width * j + i;
183  }
184 
185  inline unsigned mapIdx(const octomap::OcTreeKey& key) const {
186  return mapIdx((key[0] - m_paddedMinKey[0]) / m_multires2DScale,
187  (key[1] - m_paddedMinKey[1]) / m_multires2DScale);
188 
189  }
190 
197  void adjustMapData(nav_msgs::OccupancyGrid& map, const nav_msgs::MapMetaData& oldMapInfo) const;
198 
199  inline bool mapChanged(const nav_msgs::MapMetaData& oldMapInfo, const nav_msgs::MapMetaData& newMapInfo) {
200  return ( oldMapInfo.height != newMapInfo.height
201  || oldMapInfo.width != newMapInfo.width
202  || oldMapInfo.origin.position.x != newMapInfo.origin.position.x
203  || oldMapInfo.origin.position.y != newMapInfo.origin.position.y);
204  }
205 
206  static std_msgs::ColorRGBA heightMapColor(double h);
214  boost::recursive_mutex m_config_mutex;
215  dynamic_reconfigure::Server<OctomapServerConfig> m_reconfigureServer;
216 
218  octomap::KeyRay m_keyRay; // temp storage for ray casting
221 
222  double m_minRange;
223  double m_maxRange;
224  std::string m_worldFrameId; // the map frame
225  std::string m_baseFrameId; // base of the robot for ground plane filtering
227  std_msgs::ColorRGBA m_color;
228  std_msgs::ColorRGBA m_colorFree;
230 
233 
234  double m_res;
235  unsigned m_treeDepth;
236  unsigned m_maxTreeDepth;
237 
246  double m_minSizeX;
247  double m_minSizeY;
249 
254 
256 
258 
259  // downprojected 2D map:
261  nav_msgs::OccupancyGrid m_gridmap;
268 };
269 }
270 
271 #endif
octomap_server::OctomapServer::m_resetService
ros::ServiceServer m_resetService
Definition: OctomapServer.h:212
octomap_server::OctomapServer::octomapBinarySrv
virtual bool octomapBinarySrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res)
Definition: OctomapServer.cpp:715
octomap_server::OctomapServer::m_occupancyMaxZ
double m_occupancyMaxZ
Definition: OctomapServer.h:245
octomap_server::OctomapServer::OctomapServer
OctomapServer(const ros::NodeHandle private_nh_=ros::NodeHandle("~"), const ros::NodeHandle &nh_=ros::NodeHandle())
Definition: OctomapServer.cpp:42
octomap_server::OctomapServer::m_fmapPub
ros::Publisher m_fmapPub
Definition: OctomapServer.h:209
octomap_server::OctomapServer::m_reconfigureServer
dynamic_reconfigure::Server< OctomapServerConfig > m_reconfigureServer
Definition: OctomapServer.h:215
octomap_server::OctomapServer::filterGroundPlane
void filterGroundPlane(const PCLPointCloud &pc, PCLPointCloud &ground, PCLPointCloud &nonground) const
label the input cloud "pc" into ground and nonground. Should be in the robot's fixed frame (not world...
Definition: OctomapServer.cpp:834
octomap_server::OctomapServer::handleNode
virtual void handleNode(const OcTreeT::iterator &it)
hook that is called when traversing all nodes of the updated Octree (does nothing here)
Definition: OctomapServer.h:158
octomap_server::OctomapServer::m_pointcloudMinX
double m_pointcloudMinX
Definition: OctomapServer.h:238
octomap_server::OctomapServer::m_baseFrameId
std::string m_baseFrameId
Definition: OctomapServer.h:225
octomap_server::OctomapServer::m_latchedTopics
bool m_latchedTopics
Definition: OctomapServer.h:231
octomap_server::OctomapServer::updateMaxKey
static void updateMaxKey(const octomap::OcTreeKey &in, octomap::OcTreeKey &max)
Definition: OctomapServer.h:112
ros::Publisher
octomap_server::OctomapServer::OctomapSrv
octomap_msgs::GetOctomap OctomapSrv
Definition: OctomapServer.h:93
octomap_server::OctomapServer::PCLPointCloud
pcl::PointCloud< pcl::PointXYZ > PCLPointCloud
Definition: OctomapServer.h:90
octomap_server::OctomapServer::insertCloudCallback
virtual void insertCloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud)
Definition: OctomapServer.cpp:263
octomap_server::OctomapServer::m_mapOriginChanged
bool m_mapOriginChanged
Definition: OctomapServer.h:263
octomap_server::OctomapServer::openFile
virtual bool openFile(const std::string &filename)
Definition: OctomapServer.cpp:210
octomap_server::OctomapServer::m_keyRay
octomap::KeyRay m_keyRay
Definition: OctomapServer.h:218
octomap_server::OctomapServer::m_tfPointCloudSub
tf::MessageFilter< sensor_msgs::PointCloud2 > * m_tfPointCloudSub
Definition: OctomapServer.h:211
octomap_server::OctomapServer::heightMapColor
static std_msgs::ColorRGBA heightMapColor(double h)
Definition: OctomapServer.cpp:1234
ros.h
octomap_server::OctomapServer::m_filterSpeckles
bool m_filterSpeckles
Definition: OctomapServer.h:248
octomap_server::OctomapServer::isSpeckleNode
bool isSpeckleNode(const octomap::OcTreeKey &key) const
Find speckle nodes (single occupied voxels with no neighbors). Only works on lowest resolution!
Definition: OctomapServer.cpp:1113
octomap_server::OctomapServer::resetSrv
bool resetSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
Definition: OctomapServer.cpp:763
octomap_server::OctomapServer::m_paddedMinKey
octomap::OcTreeKey m_paddedMinKey
Definition: OctomapServer.h:264
octomap_server::OctomapServer::handlePreNodeTraversal
virtual void handlePreNodeTraversal(const ros::Time &rostime)
hook that is called before traversing all nodes
Definition: OctomapServer.cpp:943
octomap_server::OctomapServer::m_pointcloudMaxY
double m_pointcloudMaxY
Definition: OctomapServer.h:241
octomap_server::OctomapServer::m_collisionObjectPub
ros::Publisher m_collisionObjectPub
Definition: OctomapServer.h:209
octomap_server::OctomapServer::octomapFullSrv
virtual bool octomapFullSrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res)
Definition: OctomapServer.cpp:730
octomap_server::OctomapServer::m_octree
OcTreeT * m_octree
Definition: OctomapServer.h:217
octomap_server::OctomapServer::m_multires2DScale
unsigned m_multires2DScale
Definition: OctomapServer.h:265
octomap::KeyRay
octomap_server::OctomapServer::m_colorFactor
double m_colorFactor
Definition: OctomapServer.h:229
octomap::ColorOcTree
octomap_server::OctomapServer::publishAll
virtual void publishAll(const ros::Time &rostime=ros::Time::now())
Definition: OctomapServer.cpp:497
octomap_server::OctomapServer::m_initConfig
bool m_initConfig
Definition: OctomapServer.h:257
octomap_server::OctomapServer::m_publishFreeSpace
bool m_publishFreeSpace
Definition: OctomapServer.h:232
octomap_server::OctomapServer::m_nh_private
ros::NodeHandle m_nh_private
Definition: OctomapServer.h:208
transforms.h
octomap_server::OctomapServer::publishBinaryOctoMap
void publishBinaryOctoMap(const ros::Time &rostime=ros::Time::now()) const
Definition: OctomapServer.cpp:808
message_filters::Subscriber< sensor_msgs::PointCloud2 >
ros::ServiceServer
octomap_server::OctomapServer::m_pointcloudMaxZ
double m_pointcloudMaxZ
Definition: OctomapServer.h:243
octomap_server::OctomapServer::m_incrementalUpdate
bool m_incrementalUpdate
Definition: OctomapServer.h:260
octomap_server::OctomapServer::m_publish2DMap
bool m_publish2DMap
Definition: OctomapServer.h:262
octomap::OcTree
octomap_server::OctomapServer::handleFreeNodeInBBX
virtual void handleFreeNodeInBBX(const OcTreeT::iterator &it)
hook that is called when traversing free nodes in the updated area (updates 2D map projection here)
Definition: OctomapServer.cpp:1075
octomap_server::OctomapServer::publishProjected2DMap
void publishProjected2DMap(const ros::Time &rostime=ros::Time::now())
Definition: OctomapServer.cpp:489
octomap_server::OctomapServer::~OctomapServer
virtual ~OctomapServer()
Definition: OctomapServer.cpp:191
octomap_server::OctomapServer::m_res
double m_res
Definition: OctomapServer.h:234
octomap_server::OctomapServer::m_cmapPub
ros::Publisher m_cmapPub
Definition: OctomapServer.h:209
octomap_server::OctomapServer::m_groundFilterAngle
double m_groundFilterAngle
Definition: OctomapServer.h:252
tf::Point
tf::Vector3 Point
octomap_eraser_cli.max
max
Definition: octomap_eraser_cli.py:24
octomap_server::OctomapServer::m_octomapFullService
ros::ServiceServer m_octomapFullService
Definition: OctomapServer.h:212
octomap_server::OctomapServer::mapChanged
bool mapChanged(const nav_msgs::MapMetaData &oldMapInfo, const nav_msgs::MapMetaData &newMapInfo)
Definition: OctomapServer.h:199
ColorOcTree.h
message_filter.h
octomap_server::OctomapServer::m_octomapBinaryService
ros::ServiceServer m_octomapBinaryService
Definition: OctomapServer.h:212
octomap_server::OctomapServer::clearBBXSrv
bool clearBBXSrv(BBXSrv::Request &req, BBXSrv::Response &resp)
Definition: OctomapServer.cpp:744
octomap_server::OctomapServer::m_nh
ros::NodeHandle m_nh
Definition: OctomapServer.h:207
octomap_server::OctomapServer::updateMinKey
static void updateMinKey(const octomap::OcTreeKey &in, octomap::OcTreeKey &min)
Definition: OctomapServer.h:107
octomap_server::OctomapServer::m_fmarkerPub
ros::Publisher m_fmarkerPub
Definition: OctomapServer.h:209
octomap_server::OctomapServer::adjustMapData
void adjustMapData(nav_msgs::OccupancyGrid &map, const nav_msgs::MapMetaData &oldMapInfo) const
Definition: OctomapServer.cpp:1193
subscriber.h
octomap_server::OctomapServer::handleFreeNode
virtual void handleFreeNode(const OcTreeT::iterator &it)
hook that is called when traversing free nodes of the updated Octree
Definition: OctomapServer.cpp:1063
octomap_server::OctomapServer::m_pointcloudMinZ
double m_pointcloudMinZ
Definition: OctomapServer.h:242
octomap_server::OctomapServer::mapIdx
unsigned mapIdx(const octomap::OcTreeKey &key) const
Definition: OctomapServer.h:185
octomap_server::OctomapServer::m_gridmap
nav_msgs::OccupancyGrid m_gridmap
Definition: OctomapServer.h:261
octomap_server::OctomapServer::m_pointcloudMaxX
double m_pointcloudMaxX
Definition: OctomapServer.h:239
octomap_server::OctomapServer::BBXSrv
octomap_msgs::BoundingBoxQuery BBXSrv
Definition: OctomapServer.h:94
octomap_server::OctomapServer::m_colorFree
std_msgs::ColorRGBA m_colorFree
Definition: OctomapServer.h:228
octomap_server::OctomapServer::m_updateBBXMin
octomap::OcTreeKey m_updateBBXMin
Definition: OctomapServer.h:219
octomap::OcTreeKey
octomap_server::OctomapServer::m_mapPub
ros::Publisher m_mapPub
Definition: OctomapServer.h:209
octomap_server::OctomapServer::insertScan
virtual void insertScan(const tf::Point &sensorOrigin, const PCLPointCloud &ground, const PCLPointCloud &nonground)
update occupancy map with a scan labeled as ground and nonground. The scans should be in the global m...
Definition: OctomapServer.cpp:357
octomap_server::OctomapServer::PCLPoint
pcl::PointXYZ PCLPoint
Definition: OctomapServer.h:89
octomap_server::OctomapServer::m_pointCloudPub
ros::Publisher m_pointCloudPub
Definition: OctomapServer.h:209
octomap_server::OctomapServer::isInUpdateBBX
bool isInUpdateBBX(const OcTreeT::iterator &it) const
Test if key is within update area of map (2D, ignores height)
Definition: OctomapServer.h:118
octomap_server
Definition: OctomapServer.h:80
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::iterator
leaf_iterator iterator
transform_listener.h
octomap_server::OctomapServer::m_compressMap
bool m_compressMap
Definition: OctomapServer.h:255
octomap_server::OctomapServer::m_updateBBXMax
octomap::OcTreeKey m_updateBBXMax
Definition: OctomapServer.h:220
ros::Time
octomap_server::OctomapServer::m_fullMapPub
ros::Publisher m_fullMapPub
Definition: OctomapServer.h:209
octomap_server::OctomapServer::m_groundFilterDistance
double m_groundFilterDistance
Definition: OctomapServer.h:251
octomap_server::OctomapServer::handleOccupiedNode
virtual void handleOccupiedNode(const OcTreeT::iterator &it)
hook that is called when traversing occupied nodes of the updated Octree
Definition: OctomapServer.cpp:1057
octomap_server::OctomapServer::m_occupancyMinZ
double m_occupancyMinZ
Definition: OctomapServer.h:244
tf::MessageFilter< sensor_msgs::PointCloud2 >
octomap_server::OctomapServer::m_minRange
double m_minRange
Definition: OctomapServer.h:222
octomap_server::OctomapServer::m_treeDepth
unsigned m_treeDepth
Definition: OctomapServer.h:235
tf::TransformListener
octomap_server::OctomapServer::mapIdx
unsigned mapIdx(int i, int j) const
Definition: OctomapServer.h:181
octomap.h
octomap_server::OctomapServer::m_clearBBXService
ros::ServiceServer m_clearBBXService
Definition: OctomapServer.h:212
octomap_server::OctomapServer::OcTreeT
octomap::OcTree OcTreeT
Definition: OctomapServer.h:91
octomap_server::OctomapServer::m_minSizeY
double m_minSizeY
Definition: OctomapServer.h:247
octomap_server::OctomapServer
Definition: OctomapServer.h:81
octomap_server::OctomapServer::m_tfListener
tf::TransformListener m_tfListener
Definition: OctomapServer.h:213
conversions.h
octomap_server::OctomapServer::m_pointCloudSub
message_filters::Subscriber< sensor_msgs::PointCloud2 > * m_pointCloudSub
Definition: OctomapServer.h:210
octomap_server::OctomapServer::m_groundFilterPlaneDistance
double m_groundFilterPlaneDistance
Definition: OctomapServer.h:253
octomap_server::OctomapServer::m_projectCompleteMap
bool m_projectCompleteMap
Definition: OctomapServer.h:266
octomap_server::OctomapServer::handleOccupiedNodeInBBX
virtual void handleOccupiedNodeInBBX(const OcTreeT::iterator &it)
hook that is called when traversing occupied nodes in the updated area (updates 2D map projection her...
Definition: OctomapServer.cpp:1069
octomap_server::OctomapServer::m_maxRange
double m_maxRange
Definition: OctomapServer.h:223
octomap_server::OctomapServer::m_useColoredMap
bool m_useColoredMap
Definition: OctomapServer.h:267
octomap_server::OctomapServer::reconfigureCallback
void reconfigureCallback(octomap_server::OctomapServerConfig &config, uint32_t level)
Definition: OctomapServer.cpp:1133
octomap_server::OctomapServer::m_pointcloudMinY
double m_pointcloudMinY
Definition: OctomapServer.h:240
octomap_server::OctomapServer::m_filterGroundPlane
bool m_filterGroundPlane
Definition: OctomapServer.h:250
octomap_server::OctomapServer::publishFullOctoMap
void publishFullOctoMap(const ros::Time &rostime=ros::Time::now()) const
Definition: OctomapServer.cpp:820
octomap_server::OctomapServer::m_maxTreeDepth
unsigned m_maxTreeDepth
Definition: OctomapServer.h:236
octomap_server::OctomapServer::m_minSizeX
double m_minSizeX
Definition: OctomapServer.h:246
octomap_server::OctomapServer::handleNodeInBBX
virtual void handleNodeInBBX(const OcTreeT::iterator &it)
hook that is called when traversing all nodes of the updated Octree in the updated area (does nothing...
Definition: OctomapServer.h:161
octomap_server::OctomapServer::m_markerPub
ros::Publisher m_markerPub
Definition: OctomapServer.h:209
OcTreeKey.h
octomap_server::OctomapServer::handlePostNodeTraversal
virtual void handlePostNodeTraversal(const ros::Time &rostime)
hook that is called after traversing all nodes
Definition: OctomapServer.cpp:1053
octomap_server::OctomapServer::m_worldFrameId
std::string m_worldFrameId
Definition: OctomapServer.h:224
ros::NodeHandle
octomap_server::OctomapServer::m_config_mutex
boost::recursive_mutex m_config_mutex
Definition: OctomapServer.h:214
octomap_server::OctomapServer::m_useHeightMap
bool m_useHeightMap
Definition: OctomapServer.h:226
octomap_server::OctomapServer::update2DMap
virtual void update2DMap(const OcTreeT::iterator &it, bool occupied)
updates the downprojected 2D map as either occupied or free
Definition: OctomapServer.cpp:1081
ros::Time::now
static Time now()
octomap_server::OctomapServer::m_color
std_msgs::ColorRGBA m_color
Definition: OctomapServer.h:227
pcl_conversions.h
octomap_server::OctomapServer::m_binaryMapPub
ros::Publisher m_binaryMapPub
Definition: OctomapServer.h:209


octomap_server
Author(s): Armin Hornung
autogenerated on Mon Jan 2 2023 03:18:15