Go to the documentation of this file.
49 #ifndef __NEARFIELD_MAP_BASE_PA_NODE_H
50 #define __NEARFIELD_MAP_BASE_PA_NODE_H
55 #include "nearfield_map/NearfieldMapFileName.h"
56 #include "nearfield_map/NearfieldMapGetSize.h"
57 #include "nearfield_map/NearfieldMapChangeSettings.h"
58 #include "nearfield_map/NearfieldMapRequest.h"
63 #include <std_msgs/Empty.h>
64 #include <std_msgs/Header.h>
66 #include <sensor_msgs/PointCloud2.h>
68 #include <std_srvs/Empty.h>
72 #include <octomap_msgs/Octomap.h>
74 #include <octomap_pa/addcloud_parameter.h>
75 #include <parameter_pa/parameter_pa_ros.h>
76 #include <pcdfilter_pa/pcdfilter_pa_ros.h>
77 #include <pcdfilter_pa/pcdfilter_pa_ros_throttle.h>
85 template <
typename NEARFIELDMAP>
169 std_srvs::Empty::Response &res);
174 nearfield_map::NearfieldMapGetSize::Request &req,
175 nearfield_map::NearfieldMapGetSize::Response &res);
180 nearfield_map::NearfieldMapFileName::Request &req,
181 nearfield_map::NearfieldMapFileName::Response &res);
185 nearfield_map::NearfieldMapFileName::Request &req,
186 nearfield_map::NearfieldMapFileName::Response &res);
191 std_srvs::Empty::Response &res);
195 nearfield_map::NearfieldMapRequest::Request &req,
196 nearfield_map::NearfieldMapRequest::Response &res);
201 nearfield_map::NearfieldMapChangeSettings::Request &req,
202 nearfield_map::NearfieldMapChangeSettings::Response &res);
206 #include "nearfield_map_base_pa_node.hxx"
208 #endif // __NEARFIELD_MAP_BASE_PA_NODE_H
ros::Publisher pub_nearfield_
puplisher for requested nearfield map (pointcloud)
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
void changeSettings(void)
ros::ServiceServer srv_save_
service for saving the octomap
ros::Subscriber sub_camera_
subscriber for depth images from camera
bool checkTF(const std_msgs::Header &header, tf::StampedTransform &transform)
ros::ServiceServer srv_change_settings_
service for changing parameters of the nearfield map
cAddCloudParameter params_addcloud_camera_
parameter for insertion of depth images from camera
ros::ServiceServer srv_load_
service for loading a octomap
bool getSizeCallbackSrv(nearfield_map::NearfieldMapGetSize::Request &req, nearfield_map::NearfieldMapGetSize::Response &res)
cNearfieldMapBasePaNode< NEARFIELDMAP > MapTypeFull
int count_camera_
number of inserted depth images from camera (pointclouds)
ros::Publisher pub_octomap_
puplisher for the octomap (binary data)
bool loadCallbackSrv(nearfield_map::NearfieldMapFileName::Request &req, nearfield_map::NearfieldMapFileName::Response &res)
bool clearCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
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
cAddCloudParameter params_addcloud_laser_scan_
parameter for insertion of single laserscans
bool sendCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
int count_laser_full_
number of inserted full laserscans (pointclouds)
int count_laser_scan_
number of inserted single laserscans
cNearfieldMapBasePaNode()
default constructor
bool saveCallbackSrv(nearfield_map::NearfieldMapFileName::Request &req, nearfield_map::NearfieldMapFileName::Response &res)
cAddCloudParameter params_addcloud_laser_full_
parameter for insertion of full laserscans
void clearCallbackSub(const std_msgs::EmptyConstPtr &msg)
bool requestCallbackSrv(nearfield_map::NearfieldMapRequest::Request &req, nearfield_map::NearfieldMapRequest::Response &res)
ros::Subscriber sub_clear_
subscriber for clearing the octomap
~cNearfieldMapBasePaNode()
default destructor
ros::ServiceServer srv_getsize_
service for receiving the size of the octomap
cPcdFilterPaRosThrottle output_throttle_
void publish(void)
function for publishing all topics (nearfield map and debugging)
bool getNearfield(sensor_msgs::PointCloud2Ptr &msg)
function for retrieving requested nearfield map as pointcloud
cPcdFilterPaRos output_filter_
ros::ServiceServer srv_clear_
service for clearing the octomap
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::Publisher pub_octomap_full_
puplisher for the octomap (full data)
cNearfieldMapPaNodeParameter nodeparams_
parameters
ros::Publisher pub_cloud_occupied_
puplisher for occupied voxels as pointcloud
ros::Subscriber sub_laser_scan_
subscriber for a laserscan
nearfield_map
Author(s):
autogenerated on Wed Mar 2 2022 00:42:09