46 #ifndef __NEARFIELD_MAP_BASE_PA_NODE_H 47 #define __NEARFIELD_MAP_BASE_PA_NODE_H 52 #include "nearfield_map/NearfieldMapFileName.h" 53 #include "nearfield_map/NearfieldMapGetSize.h" 54 #include "nearfield_map/NearfieldMapChangeSettings.h" 55 #include "nearfield_map/NearfieldMapRequest.h" 60 #include <std_msgs/Empty.h> 61 #include <std_msgs/Header.h> 63 #include <sensor_msgs/PointCloud2.h> 65 #include <std_srvs/Empty.h> 69 #include <octomap_msgs/Octomap.h> 82 template <
typename NEARFIELDMAP>
103 bool checkTF(
const std_msgs::Header &header,
166 std_srvs::Empty::Response &res);
171 nearfield_map::NearfieldMapGetSize::Request &req,
172 nearfield_map::NearfieldMapGetSize::Response &res);
177 nearfield_map::NearfieldMapFileName::Request &req,
178 nearfield_map::NearfieldMapFileName::Response &res);
182 nearfield_map::NearfieldMapFileName::Request &req,
183 nearfield_map::NearfieldMapFileName::Response &res);
188 std_srvs::Empty::Response &res);
192 nearfield_map::NearfieldMapRequest::Request &req,
193 nearfield_map::NearfieldMapRequest::Response &res);
198 nearfield_map::NearfieldMapChangeSettings::Request &req,
199 nearfield_map::NearfieldMapChangeSettings::Response &res);
203 #include "nearfield_map_base_pa_node.hxx" 205 #endif // __NEARFIELD_MAP_BASE_PA_NODE_H ros::ServiceServer srv_send_
service for requesting a nearfield map (pointcloud) via output topic
ros::NodeHandle nh_
node handler for topic subscription and advertising
ros::Subscriber sub_laser_scan_
subscriber for a laserscan
ros::ServiceServer srv_load_
service for loading a octomap
void changeSettings(void)
cNearfieldMapPaNodeParameter nodeparams_
parameters
int count_camera_
number of inserted depth images from camera (pointclouds)
ros::Subscriber sub_laser_full_
subscriber for single laserscans
ros::Publisher pub_cloud_free_
puplisher for free voxels as pointcloud
tf::TransformListener tf_listener_
transformation of different frames
ros::ServiceServer srv_save_
service for saving the octomap
bool checkTF(const std_msgs::Header &header, tf::StampedTransform &transform)
bool sendCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer srv_change_settings_
service for changing parameters of the nearfield map
cAddCloudParameter params_addcloud_laser_scan_
parameter for insertion of single laserscans
ros::Publisher pub_octomap_
puplisher for the octomap (binary data)
bool getSizeCallbackSrv(nearfield_map::NearfieldMapGetSize::Request &req, nearfield_map::NearfieldMapGetSize::Response &res)
int count_laser_full_
number of inserted full laserscans (pointclouds)
bool saveCallbackSrv(nearfield_map::NearfieldMapFileName::Request &req, nearfield_map::NearfieldMapFileName::Response &res)
cAddCloudParameter params_addcloud_camera_
parameter for insertion of depth images from camera
bool loadCallbackSrv(nearfield_map::NearfieldMapFileName::Request &req, nearfield_map::NearfieldMapFileName::Response &res)
cNearfieldMapBasePaNode< NEARFIELDMAP > MapTypeFull
cNearfieldMapBasePaNode()
default constructor
bool changeSettingsCallbackSrv(nearfield_map::NearfieldMapChangeSettings::Request &req, nearfield_map::NearfieldMapChangeSettings::Response &res)
ros::ServiceServer srv_request_
service for requesting a nearfield map (pointcloud) via this service
bool clearCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool requestCallbackSrv(nearfield_map::NearfieldMapRequest::Request &req, nearfield_map::NearfieldMapRequest::Response &res)
~cNearfieldMapBasePaNode()
default destructor
int count_laser_scan_
number of inserted single laserscans
void clearCallbackSub(const std_msgs::EmptyConstPtr &msg)
cAddCloudParameter params_addcloud_laser_full_
parameter for insertion of full laserscans
ros::Subscriber sub_clear_
subscriber for clearing the octomap
void publish(void)
function for publishing all topics (nearfield map and debugging)
ros::ServiceServer srv_getsize_
service for receiving the size of the octomap
cPcdFilterPaRosThrottle output_throttle_
ros::Publisher pub_cloud_occupied_
puplisher for occupied voxels as pointcloud
cPcdFilterPaRos output_filter_
bool getNearfield(sensor_msgs::PointCloud2Ptr &msg)
function for retrieving requested nearfield map as pointcloud
ros::Publisher pub_octomap_full_
puplisher for the octomap (full data)
ros::Publisher pub_nearfield_
puplisher for requested nearfield map (pointcloud)
ros::ServiceServer srv_clear_
service for clearing the octomap
ros::Subscriber sub_camera_
subscriber for depth images from camera