octree_base_pa_node.h
Go to the documentation of this file.
1 /******************************************************************************
2 * *
3 * octree_base_pa_node.h *
4 * ===================== *
5 * *
6 *******************************************************************************
7 * *
8 * Repository: *
9 * https://github.com/TUC-ProAut/ros_octomap *
10 * *
11 * Chair of Automation Technology, Technische Universität Chemnitz *
12 * https://www.tu-chemnitz.de/etit/proaut *
13 * *
14 * Author: *
15 * Peter Weissig *
16 * *
17 *******************************************************************************
18 * *
19 * New BSD License *
20 * *
21 * Copyright (c) 2015-2021 TU Chemnitz *
22 * All rights reserved. *
23 * *
24 * Redistribution and use in source and binary forms, with or without *
25 * modification, are permitted provided that the following conditions are met: *
26 * * Redistributions of source code must retain the above copyright notice, *
27 * this list of conditions and the following disclaimer. *
28 * * Redistributions in binary form must reproduce the above copyright *
29 * notice, this list of conditions and the following disclaimer in the *
30 * documentation and/or other materials provided with the distribution. *
31 * * Neither the name of the copyright holder nor the names of its *
32 * contributors may be used to endorse or promote products derived from *
33 * this software without specific prior written permission. *
34 * *
35 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS *
36 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED *
37 * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR *
38 * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR *
39 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, *
40 * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, *
41 * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; *
42 * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, *
43 * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR *
44 * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF *
45 * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *
46 * *
47 ******************************************************************************/
48 
49 #ifndef __BASECLASS_BASE_PA_NODE_H
50 #define __BASECLASS_BASE_PA_NODE_H
51 
52 // local headers
55 
56 #include "octomap_pa_msgs/Reset.h"
57 #include "octomap_pa_msgs/SetConfigInsertion.h"
58 #include "octomap_pa_msgs/SetConfigDegrading.h"
59 #include "octomap_pa_msgs/GetConfig.h"
60 
61 #include "octomap_pa_msgs/AddCloud.h"
62 #include "octomap_pa_msgs/AddCloudTf.h"
63 #include "octomap_pa_msgs/GetCloud.h"
64 #include "octomap_pa_msgs/GetSize.h"
65 
66 #include "octomap_pa_msgs/FileName.h"
67 
68 // ros headers
69 #include <ros/ros.h>
70 
71 #include <geometry_msgs/Point.h>
72 #include <sensor_msgs/PointCloud.h>
73 #include <sensor_msgs/PointCloud2.h>
74 #include <sensor_msgs/LaserScan.h>
75 #include <nav_msgs/Path.h>
76 #include <std_srvs/Empty.h>
77 
78 #include <octomap_msgs/Octomap.h>
79 
80 #include <tf/transform_datatypes.h>
81 
82 // additional libraries
83 #include <pcl/point_cloud.h>
84 #include <pcl/point_types.h>
85 
86 #include <octomap/octomap.h>
87 
88 //**************************[cOctreeBasePaNode]********************************
89 template <typename BASECLASS>
90 class cOctreeBasePaNode : public BASECLASS {
91  public:
92 
93  typedef BASECLASS TypeBase;
95 
97  cOctreeBasePaNode(const std::string nodename,
98  const double resolution = 0.1,
99  const ros::Duration tf_listener_buffersize = ros::Duration(20));
100 
102  virtual ~cOctreeBasePaNode();
103 
105  void publishOctomap(void);
106 
108  virtual octomap_pa_msgs::Config getConfig(void);
110  bool setConfigInsertion(const octomap_pa_msgs::ConfigInsertion &config);
112  virtual bool setConfigDegrading(
113  const octomap_pa_msgs::ConfigDegrading &config);
114 
115  protected:
116 
120 
127 
130 
133 
134 
139  const sensor_msgs::PointCloud2ConstPtr &msg);
140 
145  const sensor_msgs::PointCloudConstPtr &msg);
146 
150  void addLaserCallbackSub(const sensor_msgs::LaserScanConstPtr &msg);
151 
160 
161 
164  bool clearCallbackSrv(std_srvs::Empty::Request &req,
165  std_srvs::Empty::Response &res);
169  bool resetCallbackSrv(
170  octomap_pa_msgs::Reset::Request &req,
171  octomap_pa_msgs::Reset::Response &res);
172 
176  octomap_pa_msgs::SetConfigDegrading::Request &req,
177  octomap_pa_msgs::SetConfigDegrading::Response &res);
181  octomap_pa_msgs::SetConfigInsertion::Request &req,
182  octomap_pa_msgs::SetConfigInsertion::Response &res);
186  octomap_pa_msgs::GetConfig::Request &req,
187  octomap_pa_msgs::GetConfig::Response &res);
188 
191  bool addCloudCallbackSrv(
192  octomap_pa_msgs::AddCloud::Request &req,
193  octomap_pa_msgs::AddCloud::Response &res);
197  octomap_pa_msgs::AddCloudTf::Request &req,
198  octomap_pa_msgs::AddCloudTf::Response &res);
201  bool getCloudCallbackSrv(
202  octomap_pa_msgs::GetCloud::Request &req,
203  octomap_pa_msgs::GetCloud::Response &res);
206  bool getSizeCallbackSrv(
207  octomap_pa_msgs::GetSize::Request &req,
208  octomap_pa_msgs::GetSize::Response &res);
209 
212  bool saveCallbackSrv(
213  octomap_pa_msgs::FileName::Request &req,
214  octomap_pa_msgs::FileName::Response &res);
217  bool loadCallbackSrv(
218  octomap_pa_msgs::FileName::Request &req,
219  octomap_pa_msgs::FileName::Response &res);
220 
222  bool updateTimeAndGetTF(const std_msgs::Header header,
223  tf::Transform &transform);
224 
226  virtual void internal_node_update(void) = 0;
227 
228 
229  private:
231  std::string nodename_;
232 };
233 
234 #include "octomap_pa/octree_base_pa_node.hxx"
235 
236 #endif // __BASECLASS_BASE_PA_NODE_H
bool loadCallbackSrv(octomap_pa_msgs::FileName::Request &req, octomap_pa_msgs::FileName::Response &res)
std::string nodename_
official node name used for ros info messages
ros::ServiceServer srv_setconfig_degrading_
service for setting the degrading config of the octomap
cOctreeBasePaNode< BASECLASS > TypeFull
ros::Subscriber sub_cloud_old_
subscriber for a pointcloud (old format)
ros::Publisher pub_octomap_
puplisher for the octomap (binary data)
void addPointcloudOldCallbackSub(const sensor_msgs::PointCloudConstPtr &msg)
callback function for receiving a pointcloud (old format)
bool updateTimeAndGetTF(const std_msgs::Header header, tf::Transform &transform)
helper function to update/check timestamps & check/retrieve TF
cOctreeBasePaNodeParameter nodeparams_
parameters
ros::ServiceServer srv_save_
service for saving the octomap
ros::Subscriber sub_cloud_
subscriber for a pointcloud
virtual void internal_node_update(void)=0
virtual overload for additional updates
ros::Publisher pub_cloud_free_
puplisher for free voxels as pointcloud
ros::Publisher pub_cloud_occupied_
puplisher for occupied voxels as pointcloud
bool addCloudTfCallbackSrv(octomap_pa_msgs::AddCloudTf::Request &req, octomap_pa_msgs::AddCloudTf::Response &res)
bool getConfigCallbackSrv(octomap_pa_msgs::GetConfig::Request &req, octomap_pa_msgs::GetConfig::Response &res)
void publishOctomap(void)
function for publishing the octomap
virtual bool setConfigDegrading(const octomap_pa_msgs::ConfigDegrading &config)
function for setting degrading configs (does nothing by default
ros::ServiceServer srv_addcloud_
service for adding a new pointcloud to the octomap
ros::NodeHandle nh_
node handler for topic subscription and advertising
bool setConfigDegradingCallbackSrv(octomap_pa_msgs::SetConfigDegrading::Request &req, octomap_pa_msgs::SetConfigDegrading::Response &res)
ros::ServiceServer srv_getcloud_
service for receiving the current octomap as pointcloud
virtual octomap_pa_msgs::Config getConfig(void)
function for retrieving all current configs
bool addCloudCallbackSrv(octomap_pa_msgs::AddCloud::Request &req, octomap_pa_msgs::AddCloud::Response &res)
cOctreeBasePaNode(const std::string nodename, const double resolution=0.1, const ros::Duration tf_listener_buffersize=ros::Duration(20))
default constructor
virtual ~cOctreeBasePaNode()
default destructor
ros::ServiceServer srv_getconfig_
service for receiving all config of the octomap
ros::ServiceServer srv_getsize_
service for receiving the current size of the octomap
ros::ServiceServer srv_reset_
void addLaserCallbackSub(const sensor_msgs::LaserScanConstPtr &msg)
callback function for receiving a laserscan
ros::ServiceServer srv_setconfig_insertion_
service for setting the insertion config of the octomap
ros::ServiceServer srv_clear_
service for clearing the octomap
bool saveCallbackSrv(octomap_pa_msgs::FileName::Request &req, octomap_pa_msgs::FileName::Response &res)
bool setConfigInsertion(const octomap_pa_msgs::ConfigInsertion &config)
function for setting config for adding pointclouds
int count_cloud_
number of inserted pointclouds
cAddCloudParameter addparams_
bool getCloudCallbackSrv(octomap_pa_msgs::GetCloud::Request &req, octomap_pa_msgs::GetCloud::Response &res)
bool getSizeCallbackSrv(octomap_pa_msgs::GetSize::Request &req, octomap_pa_msgs::GetSize::Response &res)
ros::ServiceServer srv_load_
service for loading a octomap
ros::Publisher pub_octomap_full_
puplisher for the octomap (full data)
bool resetCallbackSrv(octomap_pa_msgs::Reset::Request &req, octomap_pa_msgs::Reset::Response &res)
ros::ServiceServer srv_addcloudtf_
service for adding a new pointcloud to the octomap (by passing a tf)
bool setConfigInsertionCallbackSrv(octomap_pa_msgs::SetConfigInsertion::Request &req, octomap_pa_msgs::SetConfigInsertion::Response &res)
tf::TransformListener tf_listener_
transformation of different frames
void addPointcloudCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a pointcloud
int count_cloud_old_
number of inserted pointclouds (old format)
ros::Subscriber sub_laser_
subscriber for a laserscan
bool clearCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
int count_laser_
number of inserted laser scans


octomap_pa
Author(s):
autogenerated on Mon Feb 28 2022 23:02:35