#include <octree_stamped_native_node.h>

Public Member Functions | |
| cOctreeStampedNativeNode () | |
| default constructor | |
| void | publishOctomap (void) |
| function for publishing the octomap | |
| ~cOctreeStampedNativeNode () | |
| 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 | |
Definition at line 82 of file octree_stamped_native_node.h.
default constructor
Definition at line 67 of file octree_stamped_native_node.cpp.
default destructor
Definition at line 177 of file octree_stamped_native_node.cpp.
| void cOctreeStampedNativeNode::addLaserCallbackSub | ( | const sensor_msgs::LaserScanConstPtr & | msg | ) | [protected] |
callback function for receiving a laserscan
Definition at line 256 of file octree_stamped_native_node.cpp.
| void cOctreeStampedNativeNode::addPointcloudCallbackSub | ( | const sensor_msgs::PointCloud2ConstPtr & | msg | ) | [protected] |
callback function for receiving a pointcloud
Definition at line 200 of file octree_stamped_native_node.cpp.
| void cOctreeStampedNativeNode::addPointcloudOldCallbackSub | ( | const sensor_msgs::PointCloudConstPtr & | msg | ) | [protected] |
callback function for receiving a pointcloud (old format)
Definition at line 228 of file octree_stamped_native_node.cpp.
| bool cOctreeStampedNativeNode::clearCallbackSrv | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) | [protected] |
Definition at line 286 of file octree_stamped_native_node.cpp.
| bool cOctreeStampedNativeNode::getSizeCallbackSrv | ( | octomap_pa::OctomapPaGetSize::Request & | req, |
| octomap_pa::OctomapPaGetSize::Response & | res | ||
| ) | [protected] |
Definition at line 302 of file octree_stamped_native_node.cpp.
| bool cOctreeStampedNativeNode::loadCallbackSrv | ( | octomap_pa::OctomapPaFileName::Request & | req, |
| octomap_pa::OctomapPaFileName::Response & | res | ||
| ) | [protected] |
Definition at line 337 of file octree_stamped_native_node.cpp.
| void cOctreeStampedNativeNode::publishOctomap | ( | void | ) |
function for publishing the octomap
Definition at line 182 of file octree_stamped_native_node.cpp.
| bool cOctreeStampedNativeNode::saveCallbackSrv | ( | octomap_pa::OctomapPaFileName::Request & | req, |
| octomap_pa::OctomapPaFileName::Response & | res | ||
| ) | [protected] |
Definition at line 319 of file octree_stamped_native_node.cpp.
Definition at line 97 of file octree_stamped_native_node.h.
int cOctreeStampedNativeNode::count_cloud_ [protected] |
number of inserted pointclouds
Definition at line 100 of file octree_stamped_native_node.h.
int cOctreeStampedNativeNode::count_cloud_old_ [protected] |
number of inserted pointclouds (old format)
Definition at line 102 of file octree_stamped_native_node.h.
int cOctreeStampedNativeNode::count_laser_ [protected] |
number of inserted laser scans
Definition at line 104 of file octree_stamped_native_node.h.
ros::NodeHandle cOctreeStampedNativeNode::nh_ [protected] |
node handler for topic subscription and advertising
Definition at line 107 of file octree_stamped_native_node.h.
parameters
Definition at line 96 of file octree_stamped_native_node.h.
puplisher for free voxels as pointcloud
Definition at line 135 of file octree_stamped_native_node.h.
puplisher for occupied voxels as pointcloud
Definition at line 137 of file octree_stamped_native_node.h.
ros::Publisher cOctreeStampedNativeNode::pub_octomap_ [protected] |
puplisher for the octomap (binary data)
Definition at line 131 of file octree_stamped_native_node.h.
puplisher for the octomap (full data)
Definition at line 133 of file octree_stamped_native_node.h.
service for clearing the octomap
Definition at line 141 of file octree_stamped_native_node.h.
service for receiving the size of the octomap
Definition at line 146 of file octree_stamped_native_node.h.
service for loading a octomap
Definition at line 156 of file octree_stamped_native_node.h.
service for saving the octomap
Definition at line 151 of file octree_stamped_native_node.h.
ros::Subscriber cOctreeStampedNativeNode::sub_cloud_ [protected] |
subscriber for a pointcloud
Definition at line 114 of file octree_stamped_native_node.h.
subscriber for a pointcloud (old format)
Definition at line 120 of file octree_stamped_native_node.h.
ros::Subscriber cOctreeStampedNativeNode::sub_laser_ [protected] |
subscriber for a laserscan
Definition at line 126 of file octree_stamped_native_node.h.
transformation of different frames
Definition at line 110 of file octree_stamped_native_node.h.