Go to the documentation of this file.
49 #ifndef __BASECLASS_BASE_PA_NODE_H
50 #define __BASECLASS_BASE_PA_NODE_H
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"
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"
66 #include "octomap_pa_msgs/FileName.h"
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>
78 #include <octomap_msgs/Octomap.h>
83 #include <pcl/point_cloud.h>
84 #include <pcl/point_types.h>
86 #include <octomap/octomap.h>
89 template <
typename BASECLASS>
98 const double resolution = 0.1,
108 virtual octomap_pa_msgs::Config
getConfig(
void);
113 const octomap_pa_msgs::ConfigDegrading &config);
139 const sensor_msgs::PointCloud2ConstPtr &msg);
145 const sensor_msgs::PointCloudConstPtr &msg);
165 std_srvs::Empty::Response &res);
170 octomap_pa_msgs::Reset::Request &req,
171 octomap_pa_msgs::Reset::Response &res);
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);
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);
202 octomap_pa_msgs::GetCloud::Request &req,
203 octomap_pa_msgs::GetCloud::Response &res);
207 octomap_pa_msgs::GetSize::Request &req,
208 octomap_pa_msgs::GetSize::Response &res);
213 octomap_pa_msgs::FileName::Request &req,
214 octomap_pa_msgs::FileName::Response &res);
218 octomap_pa_msgs::FileName::Request &req,
219 octomap_pa_msgs::FileName::Response &res);
234 #include "octomap_pa/octree_base_pa_node.hxx"
236 #endif // __BASECLASS_BASE_PA_NODE_H
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)
int count_laser_
number of inserted laser scans
ros::ServiceServer srv_setconfig_degrading_
service for setting the degrading config of the octomap
ros::Subscriber sub_laser_
subscriber for a laserscan
bool clearCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool loadCallbackSrv(octomap_pa_msgs::FileName::Request &req, octomap_pa_msgs::FileName::Response &res)
ros::Publisher pub_cloud_occupied_
puplisher for occupied voxels as pointcloud
std::string nodename_
official node name used for ros info messages
bool getConfigCallbackSrv(octomap_pa_msgs::GetConfig::Request &req, octomap_pa_msgs::GetConfig::Response &res)
ros::ServiceServer srv_addcloud_
service for adding a new pointcloud to the octomap
bool setConfigDegradingCallbackSrv(octomap_pa_msgs::SetConfigDegrading::Request &req, octomap_pa_msgs::SetConfigDegrading::Response &res)
ros::ServiceServer srv_save_
service for saving the octomap
ros::Publisher pub_cloud_free_
puplisher for free voxels as pointcloud
bool updateTimeAndGetTF(const std_msgs::Header header, tf::Transform &transform)
helper function to update/check timestamps & check/retrieve TF
bool addCloudTfCallbackSrv(octomap_pa_msgs::AddCloudTf::Request &req, octomap_pa_msgs::AddCloudTf::Response &res)
virtual bool setConfigDegrading(const octomap_pa_msgs::ConfigDegrading &config)
function for setting degrading configs (does nothing by default
ros::ServiceServer srv_getcloud_
service for receiving the current octomap as pointcloud
ros::Subscriber sub_cloud_
subscriber for a pointcloud
cOctreeBasePaNodeParameter nodeparams_
parameters
void publishOctomap(void)
function for publishing the octomap
ros::ServiceServer srv_getsize_
service for receiving the current size of the octomap
virtual octomap_pa_msgs::Config getConfig(void)
function for retrieving all current configs
virtual void internal_node_update(void)=0
virtual overload for additional updates
ros::ServiceServer srv_getconfig_
service for receiving all config of the octomap
ros::ServiceServer srv_clear_
service for clearing the octomap
cOctreeBasePaNode(const std::string nodename, const double resolution=0.1, const ros::Duration tf_listener_buffersize=ros::Duration(20))
default constructor
ros::NodeHandle nh_
node handler for topic subscription and advertising
virtual ~cOctreeBasePaNode()
default destructor
bool addCloudCallbackSrv(octomap_pa_msgs::AddCloud::Request &req, octomap_pa_msgs::AddCloud::Response &res)
bool getSizeCallbackSrv(octomap_pa_msgs::GetSize::Request &req, octomap_pa_msgs::GetSize::Response &res)
ros::ServiceServer srv_addcloudtf_
service for adding a new pointcloud to the octomap (by passing a tf)
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
bool getCloudCallbackSrv(octomap_pa_msgs::GetCloud::Request &req, octomap_pa_msgs::GetCloud::Response &res)
ros::ServiceServer srv_reset_
void addLaserCallbackSub(const sensor_msgs::LaserScanConstPtr &msg)
callback function for receiving a laserscan
cAddCloudParameter addparams_
int count_cloud_old_
number of inserted pointclouds (old format)
ros::ServiceServer srv_setconfig_insertion_
service for setting the insertion config of the octomap
tf::TransformListener tf_listener_
transformation of different frames
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)
cOctreeBasePaNode< BASECLASS > TypeFull
ros::Subscriber sub_cloud_old_
subscriber for a pointcloud (old format)
bool setConfigInsertionCallbackSrv(octomap_pa_msgs::SetConfigInsertion::Request &req, octomap_pa_msgs::SetConfigInsertion::Response &res)
void addPointcloudCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a pointcloud
octomap_pa
Author(s):
autogenerated on Wed Mar 2 2022 00:46:31