Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
cOctreeBasePaNode< BASECLASS > Class Template Referenceabstract

#include <octree_base_pa_node.h>

Inheritance diagram for cOctreeBasePaNode< BASECLASS >:
Inheritance graph
[legend]

Public Types

typedef BASECLASS TypeBase
 
typedef cOctreeBasePaNode< BASECLASS > TypeFull
 

Public Member Functions

 cOctreeBasePaNode (const std::string nodename, const double resolution=0.1, const ros::Duration tf_listener_buffersize=ros::Duration(20))
 default constructor More...
 
virtual octomap_pa_msgs::Config getConfig (void)
 function for retrieving all current configs More...
 
void publishOctomap (void)
 function for publishing the octomap More...
 
virtual bool setConfigDegrading (const octomap_pa_msgs::ConfigDegrading &config)
 function for setting degrading configs (does nothing by default More...
 
bool setConfigInsertion (const octomap_pa_msgs::ConfigInsertion &config)
 function for setting config for adding pointclouds More...
 
virtual ~cOctreeBasePaNode ()
 default destructor More...
 

Protected Member Functions

bool addCloudCallbackSrv (octomap_pa_msgs::AddCloud::Request &req, octomap_pa_msgs::AddCloud::Response &res)
 
bool addCloudTfCallbackSrv (octomap_pa_msgs::AddCloudTf::Request &req, octomap_pa_msgs::AddCloudTf::Response &res)
 
void addLaserCallbackSub (const sensor_msgs::LaserScanConstPtr &msg)
 callback function for receiving a laserscan More...
 
void addPointcloudCallbackSub (const sensor_msgs::PointCloud2ConstPtr &msg)
 callback function for receiving a pointcloud More...
 
void addPointcloudOldCallbackSub (const sensor_msgs::PointCloudConstPtr &msg)
 callback function for receiving a pointcloud (old format) More...
 
bool clearCallbackSrv (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 
bool getCloudCallbackSrv (octomap_pa_msgs::GetCloud::Request &req, octomap_pa_msgs::GetCloud::Response &res)
 
bool getConfigCallbackSrv (octomap_pa_msgs::GetConfig::Request &req, octomap_pa_msgs::GetConfig::Response &res)
 
bool getSizeCallbackSrv (octomap_pa_msgs::GetSize::Request &req, octomap_pa_msgs::GetSize::Response &res)
 
virtual void internal_node_update (void)=0
 virtual overload for additional updates More...
 
bool loadCallbackSrv (octomap_pa_msgs::FileName::Request &req, octomap_pa_msgs::FileName::Response &res)
 
bool resetCallbackSrv (octomap_pa_msgs::Reset::Request &req, octomap_pa_msgs::Reset::Response &res)
 
bool saveCallbackSrv (octomap_pa_msgs::FileName::Request &req, octomap_pa_msgs::FileName::Response &res)
 
bool setConfigDegradingCallbackSrv (octomap_pa_msgs::SetConfigDegrading::Request &req, octomap_pa_msgs::SetConfigDegrading::Response &res)
 
bool setConfigInsertionCallbackSrv (octomap_pa_msgs::SetConfigInsertion::Request &req, octomap_pa_msgs::SetConfigInsertion::Response &res)
 
bool updateTimeAndGetTF (const std_msgs::Header header, tf::Transform &transform)
 helper function to update/check timestamps & check/retrieve TF More...
 

Protected Attributes

cAddCloudParameter addparams_
 
int count_cloud_
 number of inserted pointclouds More...
 
int count_cloud_old_
 number of inserted pointclouds (old format) More...
 
int count_laser_
 number of inserted laser scans More...
 
ros::NodeHandle nh_
 node handler for topic subscription and advertising More...
 
cOctreeBasePaNodeParameter nodeparams_
 parameters More...
 
ros::Publisher pub_cloud_free_
 puplisher for free voxels as pointcloud More...
 
ros::Publisher pub_cloud_occupied_
 puplisher for occupied voxels as pointcloud More...
 
ros::Publisher pub_octomap_
 puplisher for the octomap (binary data) More...
 
ros::Publisher pub_octomap_full_
 puplisher for the octomap (full data) More...
 
ros::ServiceServer srv_addcloud_
 service for adding a new pointcloud to the octomap More...
 
ros::ServiceServer srv_addcloudtf_
 service for adding a new pointcloud to the octomap (by passing a tf) More...
 
ros::ServiceServer srv_clear_
 service for clearing the octomap More...
 
ros::ServiceServer srv_getcloud_
 service for receiving the current octomap as pointcloud More...
 
ros::ServiceServer srv_getconfig_
 service for receiving all config of the octomap More...
 
ros::ServiceServer srv_getsize_
 service for receiving the current size of the octomap More...
 
ros::ServiceServer srv_load_
 service for loading a octomap More...
 
ros::ServiceServer srv_reset_
 
ros::ServiceServer srv_save_
 service for saving the octomap More...
 
ros::ServiceServer srv_setconfig_degrading_
 service for setting the degrading config of the octomap More...
 
ros::ServiceServer srv_setconfig_insertion_
 service for setting the insertion config of the octomap More...
 
ros::Subscriber sub_cloud_
 subscriber for a pointcloud More...
 
ros::Subscriber sub_cloud_old_
 subscriber for a pointcloud (old format) More...
 
ros::Subscriber sub_laser_
 subscriber for a laserscan More...
 
tf::TransformListener tf_listener_
 transformation of different frames More...
 

Private Attributes

std::string nodename_
 official node name used for ros info messages More...
 

Detailed Description

template<typename BASECLASS>
class cOctreeBasePaNode< BASECLASS >

Definition at line 90 of file octree_base_pa_node.h.

Member Typedef Documentation

◆ TypeBase

template<typename BASECLASS >
typedef BASECLASS cOctreeBasePaNode< BASECLASS >::TypeBase

Definition at line 139 of file octree_base_pa_node.h.

◆ TypeFull

template<typename BASECLASS >
typedef cOctreeBasePaNode<BASECLASS> cOctreeBasePaNode< BASECLASS >::TypeFull

Definition at line 140 of file octree_base_pa_node.h.

Constructor & Destructor Documentation

◆ cOctreeBasePaNode()

template<typename BASECLASS >
cOctreeBasePaNode< BASECLASS >::cOctreeBasePaNode ( const std::string  nodename,
const double  resolution = 0.1,
const ros::Duration  tf_listener_buffersize = ros::Duration(20) 
)

default constructor

◆ ~cOctreeBasePaNode()

template<typename BASECLASS >
virtual cOctreeBasePaNode< BASECLASS >::~cOctreeBasePaNode ( )
virtual

default destructor

Member Function Documentation

◆ addCloudCallbackSrv()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::addCloudCallbackSrv ( octomap_pa_msgs::AddCloud::Request &  req,
octomap_pa_msgs::AddCloud::Response &  res 
)
protected

◆ addCloudTfCallbackSrv()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::addCloudTfCallbackSrv ( octomap_pa_msgs::AddCloudTf::Request &  req,
octomap_pa_msgs::AddCloudTf::Response &  res 
)
protected

◆ addLaserCallbackSub()

template<typename BASECLASS >
void cOctreeBasePaNode< BASECLASS >::addLaserCallbackSub ( const sensor_msgs::LaserScanConstPtr &  msg)
protected

callback function for receiving a laserscan

◆ addPointcloudCallbackSub()

template<typename BASECLASS >
void cOctreeBasePaNode< BASECLASS >::addPointcloudCallbackSub ( const sensor_msgs::PointCloud2ConstPtr &  msg)
protected

callback function for receiving a pointcloud

◆ addPointcloudOldCallbackSub()

template<typename BASECLASS >
void cOctreeBasePaNode< BASECLASS >::addPointcloudOldCallbackSub ( const sensor_msgs::PointCloudConstPtr msg)
protected

callback function for receiving a pointcloud (old format)

◆ clearCallbackSrv()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::clearCallbackSrv ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
protected

◆ getCloudCallbackSrv()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::getCloudCallbackSrv ( octomap_pa_msgs::GetCloud::Request &  req,
octomap_pa_msgs::GetCloud::Response &  res 
)
protected

◆ getConfig()

template<typename BASECLASS >
virtual octomap_pa_msgs::Config cOctreeBasePaNode< BASECLASS >::getConfig ( void  )
virtual

function for retrieving all current configs

Reimplemented in cOctreeStampedNativeNode, and cOctreeStampedPaNode.

◆ getConfigCallbackSrv()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::getConfigCallbackSrv ( octomap_pa_msgs::GetConfig::Request &  req,
octomap_pa_msgs::GetConfig::Response &  res 
)
protected

◆ getSizeCallbackSrv()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::getSizeCallbackSrv ( octomap_pa_msgs::GetSize::Request &  req,
octomap_pa_msgs::GetSize::Response &  res 
)
protected

◆ internal_node_update()

template<typename BASECLASS >
virtual void cOctreeBasePaNode< BASECLASS >::internal_node_update ( void  )
protectedpure virtual

virtual overload for additional updates

Implemented in cOctreeStampedNativeNode, cOctreeStampedPaNode, and cOctreePaNode.

◆ loadCallbackSrv()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::loadCallbackSrv ( octomap_pa_msgs::FileName::Request &  req,
octomap_pa_msgs::FileName::Response &  res 
)
protected

◆ publishOctomap()

template<typename BASECLASS >
void cOctreeBasePaNode< BASECLASS >::publishOctomap ( void  )

function for publishing the octomap

◆ resetCallbackSrv()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::resetCallbackSrv ( octomap_pa_msgs::Reset::Request &  req,
octomap_pa_msgs::Reset::Response &  res 
)
protected

◆ saveCallbackSrv()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::saveCallbackSrv ( octomap_pa_msgs::FileName::Request &  req,
octomap_pa_msgs::FileName::Response &  res 
)
protected

◆ setConfigDegrading()

template<typename BASECLASS >
virtual bool cOctreeBasePaNode< BASECLASS >::setConfigDegrading ( const octomap_pa_msgs::ConfigDegrading &  config)
virtual

function for setting degrading configs (does nothing by default

◆ setConfigDegradingCallbackSrv()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::setConfigDegradingCallbackSrv ( octomap_pa_msgs::SetConfigDegrading::Request &  req,
octomap_pa_msgs::SetConfigDegrading::Response &  res 
)
protected

◆ setConfigInsertion()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::setConfigInsertion ( const octomap_pa_msgs::ConfigInsertion &  config)

function for setting config for adding pointclouds

◆ setConfigInsertionCallbackSrv()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::setConfigInsertionCallbackSrv ( octomap_pa_msgs::SetConfigInsertion::Request &  req,
octomap_pa_msgs::SetConfigInsertion::Response &  res 
)
protected

◆ updateTimeAndGetTF()

template<typename BASECLASS >
bool cOctreeBasePaNode< BASECLASS >::updateTimeAndGetTF ( const std_msgs::Header  header,
tf::Transform transform 
)
protected

helper function to update/check timestamps & check/retrieve TF

Member Data Documentation

◆ addparams_

template<typename BASECLASS >
cAddCloudParameter cOctreeBasePaNode< BASECLASS >::addparams_
protected

Definition at line 165 of file octree_base_pa_node.h.

◆ count_cloud_

template<typename BASECLASS >
int cOctreeBasePaNode< BASECLASS >::count_cloud_
protected

number of inserted pointclouds

Definition at line 168 of file octree_base_pa_node.h.

◆ count_cloud_old_

template<typename BASECLASS >
int cOctreeBasePaNode< BASECLASS >::count_cloud_old_
protected

number of inserted pointclouds (old format)

Definition at line 170 of file octree_base_pa_node.h.

◆ count_laser_

template<typename BASECLASS >
int cOctreeBasePaNode< BASECLASS >::count_laser_
protected

number of inserted laser scans

Definition at line 172 of file octree_base_pa_node.h.

◆ nh_

template<typename BASECLASS >
ros::NodeHandle cOctreeBasePaNode< BASECLASS >::nh_
protected

node handler for topic subscription and advertising

Definition at line 175 of file octree_base_pa_node.h.

◆ nodename_

template<typename BASECLASS >
std::string cOctreeBasePaNode< BASECLASS >::nodename_
private

official node name used for ros info messages

Definition at line 277 of file octree_base_pa_node.h.

◆ nodeparams_

template<typename BASECLASS >
cOctreeBasePaNodeParameter cOctreeBasePaNode< BASECLASS >::nodeparams_
protected

parameters

Definition at line 164 of file octree_base_pa_node.h.

◆ pub_cloud_free_

template<typename BASECLASS >
ros::Publisher cOctreeBasePaNode< BASECLASS >::pub_cloud_free_
protected

puplisher for free voxels as pointcloud

Definition at line 203 of file octree_base_pa_node.h.

◆ pub_cloud_occupied_

template<typename BASECLASS >
ros::Publisher cOctreeBasePaNode< BASECLASS >::pub_cloud_occupied_
protected

puplisher for occupied voxels as pointcloud

Definition at line 205 of file octree_base_pa_node.h.

◆ pub_octomap_

template<typename BASECLASS >
ros::Publisher cOctreeBasePaNode< BASECLASS >::pub_octomap_
protected

puplisher for the octomap (binary data)

Definition at line 199 of file octree_base_pa_node.h.

◆ pub_octomap_full_

template<typename BASECLASS >
ros::Publisher cOctreeBasePaNode< BASECLASS >::pub_octomap_full_
protected

puplisher for the octomap (full data)

Definition at line 201 of file octree_base_pa_node.h.

◆ srv_addcloud_

template<typename BASECLASS >
ros::ServiceServer cOctreeBasePaNode< BASECLASS >::srv_addcloud_
protected

service for adding a new pointcloud to the octomap

Definition at line 236 of file octree_base_pa_node.h.

◆ srv_addcloudtf_

template<typename BASECLASS >
ros::ServiceServer cOctreeBasePaNode< BASECLASS >::srv_addcloudtf_
protected

service for adding a new pointcloud to the octomap (by passing a tf)

Definition at line 241 of file octree_base_pa_node.h.

◆ srv_clear_

template<typename BASECLASS >
ros::ServiceServer cOctreeBasePaNode< BASECLASS >::srv_clear_
protected

service for clearing the octomap

Definition at line 209 of file octree_base_pa_node.h.

◆ srv_getcloud_

template<typename BASECLASS >
ros::ServiceServer cOctreeBasePaNode< BASECLASS >::srv_getcloud_
protected

service for receiving the current octomap as pointcloud

Definition at line 246 of file octree_base_pa_node.h.

◆ srv_getconfig_

template<typename BASECLASS >
ros::ServiceServer cOctreeBasePaNode< BASECLASS >::srv_getconfig_
protected

service for receiving all config of the octomap

Definition at line 230 of file octree_base_pa_node.h.

◆ srv_getsize_

template<typename BASECLASS >
ros::ServiceServer cOctreeBasePaNode< BASECLASS >::srv_getsize_
protected

service for receiving the current size of the octomap

Definition at line 251 of file octree_base_pa_node.h.

◆ srv_load_

template<typename BASECLASS >
ros::ServiceServer cOctreeBasePaNode< BASECLASS >::srv_load_
protected

service for loading a octomap

Definition at line 262 of file octree_base_pa_node.h.

◆ srv_reset_

template<typename BASECLASS >
ros::ServiceServer cOctreeBasePaNode< BASECLASS >::srv_reset_
protected

service for resetting the octomap (clearing & changing basic properties)

Definition at line 214 of file octree_base_pa_node.h.

◆ srv_save_

template<typename BASECLASS >
ros::ServiceServer cOctreeBasePaNode< BASECLASS >::srv_save_
protected

service for saving the octomap

Definition at line 257 of file octree_base_pa_node.h.

◆ srv_setconfig_degrading_

template<typename BASECLASS >
ros::ServiceServer cOctreeBasePaNode< BASECLASS >::srv_setconfig_degrading_
protected

service for setting the degrading config of the octomap

Definition at line 220 of file octree_base_pa_node.h.

◆ srv_setconfig_insertion_

template<typename BASECLASS >
ros::ServiceServer cOctreeBasePaNode< BASECLASS >::srv_setconfig_insertion_
protected

service for setting the insertion config of the octomap

Definition at line 225 of file octree_base_pa_node.h.

◆ sub_cloud_

template<typename BASECLASS >
ros::Subscriber cOctreeBasePaNode< BASECLASS >::sub_cloud_
protected

subscriber for a pointcloud

Definition at line 182 of file octree_base_pa_node.h.

◆ sub_cloud_old_

template<typename BASECLASS >
ros::Subscriber cOctreeBasePaNode< BASECLASS >::sub_cloud_old_
protected

subscriber for a pointcloud (old format)

Definition at line 188 of file octree_base_pa_node.h.

◆ sub_laser_

template<typename BASECLASS >
ros::Subscriber cOctreeBasePaNode< BASECLASS >::sub_laser_
protected

subscriber for a laserscan

Definition at line 194 of file octree_base_pa_node.h.

◆ tf_listener_

template<typename BASECLASS >
tf::TransformListener cOctreeBasePaNode< BASECLASS >::tf_listener_
protected

transformation of different frames

Definition at line 178 of file octree_base_pa_node.h.


The documentation for this class was generated from the following file:


octomap_pa
Author(s):
autogenerated on Wed Mar 2 2022 00:46:31