46 #ifndef __OCTREE_STAMPED_NATIVE_NODE_H 47 #define __OCTREE_STAMPED_NATIVE_NODE_H 54 #include "octomap_pa/OctomapPaFileName.h" 55 #include "octomap_pa/OctomapPaGetSize.h" 60 #include <geometry_msgs/Point.h> 61 #include <sensor_msgs/PointCloud.h> 62 #include <sensor_msgs/PointCloud2.h> 63 #include <nav_msgs/Path.h> 64 #include <std_srvs/Empty.h> 68 #include <octomap_msgs/Octomap.h> 73 #include <pcl/point_types.h> 117 const sensor_msgs::PointCloud2ConstPtr &msg);
123 const sensor_msgs::PointCloudConstPtr &msg);
143 std_srvs::Empty::Response &res);
148 octomap_pa::OctomapPaGetSize::Request &req,
149 octomap_pa::OctomapPaGetSize::Response &res);
153 octomap_pa::OctomapPaFileName::Request &req,
154 octomap_pa::OctomapPaFileName::Response &res);
158 octomap_pa::OctomapPaFileName::Request &req,
159 octomap_pa::OctomapPaFileName::Response &res);
162 #endif // __OCTREE_STAMPED_NATIVE_NODE_H ros::Subscriber sub_cloud_old_
subscriber for a pointcloud (old format)
ros::Subscriber sub_cloud_
subscriber for a pointcloud
ros::ServiceServer srv_save_
service for saving the octomap
void addPointcloudOldCallbackSub(const sensor_msgs::PointCloudConstPtr &msg)
callback function for receiving a pointcloud (old format)
ros::Publisher pub_cloud_free_
puplisher for free voxels as pointcloud
ros::Subscriber sub_laser_
subscriber for a laserscan
int count_cloud_
number of inserted pointclouds
cAddCloudParameter addparams_
bool loadCallbackSrv(octomap_pa::OctomapPaFileName::Request &req, octomap_pa::OctomapPaFileName::Response &res)
ros::Publisher pub_octomap_
puplisher for the octomap (binary data)
ros::ServiceServer srv_clear_
service for clearing the octomap
ros::Publisher pub_cloud_occupied_
puplisher for occupied voxels as pointcloud
~cOctreeStampedNativeNode()
default destructor
void addLaserCallbackSub(const sensor_msgs::LaserScanConstPtr &msg)
callback function for receiving a laserscan
bool getSizeCallbackSrv(octomap_pa::OctomapPaGetSize::Request &req, octomap_pa::OctomapPaGetSize::Response &res)
bool clearCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer srv_getsize_
service for receiving the size of the octomap
int count_cloud_old_
number of inserted pointclouds (old format)
cOctreeStampedNativeNode()
default constructor
void publishOctomap(void)
function for publishing the octomap
ros::Publisher pub_octomap_full_
puplisher for the octomap (full data)
cOctreeBasePaNodeParameter nodeparams_
parameters
tf::TransformListener tf_listener_
transformation of different frames
int count_laser_
number of inserted laser scans
ros::NodeHandle nh_
node handler for topic subscription and advertising
bool saveCallbackSrv(octomap_pa::OctomapPaFileName::Request &req, octomap_pa::OctomapPaFileName::Response &res)
ros::ServiceServer srv_load_
service for loading a octomap
void addPointcloudCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a pointcloud