Public Member Functions | Protected Member Functions | Protected Attributes
cOctreeStampedPaNode Class Reference

#include <octree_stamped_pa_node.h>

Inheritance diagram for cOctreeStampedPaNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 cOctreeStampedPaNode ()
 default constructor
void publishOctomap (void)
 function for publishing the octomap
 ~cOctreeStampedPaNode ()
 default destructor

Protected Member Functions

void addLaserCallbackSub (const sensor_msgs::LaserScanConstPtr &msg)
 callback function for receiving a laserscan
void addPointcloudCallbackSub (const sensor_msgs::PointCloud2ConstPtr &msg)
 callback function for receiving a pointcloud
void addPointcloudOldCallbackSub (const sensor_msgs::PointCloudConstPtr &msg)
 callback function for receiving a pointcloud (old format)
bool clearCallbackSrv (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool getSizeCallbackSrv (octomap_pa::OctomapPaGetSize::Request &req, octomap_pa::OctomapPaGetSize::Response &res)
bool loadCallbackSrv (octomap_pa::OctomapPaFileName::Request &req, octomap_pa::OctomapPaFileName::Response &res)
bool saveCallbackSrv (octomap_pa::OctomapPaFileName::Request &req, octomap_pa::OctomapPaFileName::Response &res)

Protected Attributes

cAddCloudParameter addparams_
int count_cloud_
 number of inserted pointclouds
int count_cloud_old_
 number of inserted pointclouds (old format)
int count_laser_
 number of inserted laser scans
ros::NodeHandle nh_
 node handler for topic subscription and advertising
cOctreeBasePaNodeParameter nodeparams_
 parameters
ros::Publisher pub_cloud_free_
 puplisher for free voxels as pointcloud
ros::Publisher pub_cloud_occupied_
 puplisher for occupied voxels as pointcloud
ros::Publisher pub_octomap_
 puplisher for the octomap (binary data)
ros::Publisher pub_octomap_full_
 puplisher for the octomap (full data)
ros::ServiceServer srv_clear_
 service for clearing the octomap
ros::ServiceServer srv_getsize_
 service for receiving the size of the octomap
ros::ServiceServer srv_load_
 service for loading a octomap
ros::ServiceServer srv_save_
 service for saving the octomap
ros::Subscriber sub_cloud_
 subscriber for a pointcloud
ros::Subscriber sub_cloud_old_
 subscriber for a pointcloud (old format)
ros::Subscriber sub_laser_
 subscriber for a laserscan
tf::TransformListener tf_listener_
 transformation of different frames

Detailed Description

Definition at line 82 of file octree_stamped_pa_node.h.


Constructor & Destructor Documentation

default constructor

Definition at line 67 of file octree_stamped_pa_node.cpp.

default destructor

Definition at line 178 of file octree_stamped_pa_node.cpp.


Member Function Documentation

void cOctreeStampedPaNode::addLaserCallbackSub ( const sensor_msgs::LaserScanConstPtr &  msg) [protected]

callback function for receiving a laserscan

Definition at line 257 of file octree_stamped_pa_node.cpp.

void cOctreeStampedPaNode::addPointcloudCallbackSub ( const sensor_msgs::PointCloud2ConstPtr &  msg) [protected]

callback function for receiving a pointcloud

Definition at line 201 of file octree_stamped_pa_node.cpp.

callback function for receiving a pointcloud (old format)

Definition at line 229 of file octree_stamped_pa_node.cpp.

bool cOctreeStampedPaNode::clearCallbackSrv ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected]

Definition at line 287 of file octree_stamped_pa_node.cpp.

bool cOctreeStampedPaNode::getSizeCallbackSrv ( octomap_pa::OctomapPaGetSize::Request &  req,
octomap_pa::OctomapPaGetSize::Response &  res 
) [protected]

Definition at line 303 of file octree_stamped_pa_node.cpp.

bool cOctreeStampedPaNode::loadCallbackSrv ( octomap_pa::OctomapPaFileName::Request &  req,
octomap_pa::OctomapPaFileName::Response &  res 
) [protected]

Definition at line 338 of file octree_stamped_pa_node.cpp.

function for publishing the octomap

Definition at line 183 of file octree_stamped_pa_node.cpp.

bool cOctreeStampedPaNode::saveCallbackSrv ( octomap_pa::OctomapPaFileName::Request &  req,
octomap_pa::OctomapPaFileName::Response &  res 
) [protected]

Definition at line 320 of file octree_stamped_pa_node.cpp.


Member Data Documentation

Definition at line 97 of file octree_stamped_pa_node.h.

number of inserted pointclouds

Definition at line 100 of file octree_stamped_pa_node.h.

number of inserted pointclouds (old format)

Definition at line 102 of file octree_stamped_pa_node.h.

number of inserted laser scans

Definition at line 104 of file octree_stamped_pa_node.h.

node handler for topic subscription and advertising

Definition at line 107 of file octree_stamped_pa_node.h.

parameters

Definition at line 96 of file octree_stamped_pa_node.h.

puplisher for free voxels as pointcloud

Definition at line 135 of file octree_stamped_pa_node.h.

puplisher for occupied voxels as pointcloud

Definition at line 137 of file octree_stamped_pa_node.h.

puplisher for the octomap (binary data)

Definition at line 131 of file octree_stamped_pa_node.h.

puplisher for the octomap (full data)

Definition at line 133 of file octree_stamped_pa_node.h.

service for clearing the octomap

Definition at line 141 of file octree_stamped_pa_node.h.

service for receiving the size of the octomap

Definition at line 146 of file octree_stamped_pa_node.h.

service for loading a octomap

Definition at line 156 of file octree_stamped_pa_node.h.

service for saving the octomap

Definition at line 151 of file octree_stamped_pa_node.h.

subscriber for a pointcloud

Definition at line 114 of file octree_stamped_pa_node.h.

subscriber for a pointcloud (old format)

Definition at line 120 of file octree_stamped_pa_node.h.

subscriber for a laserscan

Definition at line 126 of file octree_stamped_pa_node.h.

transformation of different frames

Definition at line 110 of file octree_stamped_pa_node.h.


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


octomap_pa
Author(s):
autogenerated on Thu Jun 6 2019 17:53:30