46 #ifndef __NEARFIELD_MAP_DEGRADING_PA_NODE_H 47 #define __NEARFIELD_MAP_DEGRADING_PA_NODE_H 52 #include "nearfield_map/NearfieldMapGetSize.h" 79 const sensor_msgs::PointCloud2ConstPtr &msg);
82 const sensor_msgs::PointCloud2ConstPtr &msg);
85 const sensor_msgs::PointCloud2ConstPtr &msg);
89 nearfield_map::NearfieldMapGetSize::Request &req,
90 nearfield_map::NearfieldMapGetSize::Response &res);
93 #endif // __NEARFIELD_MAP_DEGRADING_PA_NODE_H bool getSizeCallbackSrv(nearfield_map::NearfieldMapGetSize::Request &req, nearfield_map::NearfieldMapGetSize::Response &res)
service for receiving the size of the octomap
cNearfieldMapDegradingPaNode()
default constructor
~cNearfieldMapDegradingPaNode()
default destructor
void addPcdLaserScanCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a laserscan
void addPcdCameraCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a depth images from camera
void addPcdLaserFullCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for single laserscans