nearfield_map_base_pa_node.h
Go to the documentation of this file.
1 /******************************************************************************
2 * *
3 * nearfield_map_base_pa_node.h *
4 * ============================ *
5 * *
6 *******************************************************************************
7 * *
8 * github repository *
9 * https://github.com/TUC-ProAut/ros_nearfield_map *
10 * *
11 * Chair of Automation Technology, Technische Universität Chemnitz *
12 * https://www.tu-chemnitz.de/etit/proaut *
13 * *
14 *******************************************************************************
15 * *
16 * New BSD License *
17 * *
18 * Copyright (c) 2015-2020, Peter Weissig, Technische Universität Chemnitz *
19 * All rights reserved. *
20 * *
21 * Redistribution and use in source and binary forms, with or without *
22 * modification, are permitted provided that the following conditions are met: *
23 * * Redistributions of source code must retain the above copyright *
24 * notice, this list of conditions and the following disclaimer. *
25 * * Redistributions in binary form must reproduce the above copyright *
26 * notice, this list of conditions and the following disclaimer in the *
27 * documentation and/or other materials provided with the distribution. *
28 * * Neither the name of the Technische Universität Chemnitz nor the *
29 * names of its contributors may be used to endorse or promote products *
30 * derived from this software without specific prior written permission. *
31 * *
32 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" *
33 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE *
34 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE *
35 * ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY *
36 * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES *
37 * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR *
38 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER *
39 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT *
40 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY *
41 * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH *
42 * DAMAGE. *
43 * *
44 ******************************************************************************/
45 
46 #ifndef __NEARFIELD_MAP_BASE_PA_NODE_H
47 #define __NEARFIELD_MAP_BASE_PA_NODE_H
48 
49 // local headers
51 
52 #include "nearfield_map/NearfieldMapFileName.h"
53 #include "nearfield_map/NearfieldMapGetSize.h"
54 #include "nearfield_map/NearfieldMapChangeSettings.h"
55 #include "nearfield_map/NearfieldMapRequest.h"
56 
57 // ros headers
58 #include <ros/ros.h>
59 
60 #include <std_msgs/Empty.h>
61 #include <std_msgs/Header.h>
62 //#include <geometry_msgs/Point.h>
63 #include <sensor_msgs/PointCloud2.h>
64 //#include <nav_msgs/Path.h>
65 #include <std_srvs/Empty.h>
66 
67 #include <tf/transform_listener.h>
68 
69 #include <octomap_msgs/Octomap.h>
70 
75 
76 
77 // standard headers
78 #include <string>
79 #include <vector>
80 
81 //**************************[cNearfieldMapBasePaNode]**************************
82 template <typename NEARFIELDMAP>
83  class cNearfieldMapBasePaNode : public NEARFIELDMAP {
84  public:
85 
86  typedef NEARFIELDMAP MapTypeBase;
88 
91 
94 
96  void publish(void);
97 
99  bool getNearfield(sensor_msgs::PointCloud2Ptr &msg);
100 
103  bool checkTF(const std_msgs::Header &header,
104  tf::StampedTransform &transform);
105 
106  void changeSettings(void);
107 
108  protected:
109 
112 
119 
120 
127 
130 
133 
134  // output throttle for auto-update
136 
137  // output filter
139 
146 
157 
158 
161  void clearCallbackSub(const std_msgs::EmptyConstPtr &msg);
162 
165  bool clearCallbackSrv(std_srvs::Empty::Request &req,
166  std_srvs::Empty::Response &res);
167 
170  bool getSizeCallbackSrv(
171  nearfield_map::NearfieldMapGetSize::Request &req,
172  nearfield_map::NearfieldMapGetSize::Response &res);
173 
176  bool saveCallbackSrv(
177  nearfield_map::NearfieldMapFileName::Request &req,
178  nearfield_map::NearfieldMapFileName::Response &res);
181  bool loadCallbackSrv(
182  nearfield_map::NearfieldMapFileName::Request &req,
183  nearfield_map::NearfieldMapFileName::Response &res);
184 
187  bool sendCallbackSrv(std_srvs::Empty::Request &req,
188  std_srvs::Empty::Response &res);
191  bool requestCallbackSrv(
192  nearfield_map::NearfieldMapRequest::Request &req,
193  nearfield_map::NearfieldMapRequest::Response &res);
194 
198  nearfield_map::NearfieldMapChangeSettings::Request &req,
199  nearfield_map::NearfieldMapChangeSettings::Response &res);
200 
201 };
202 
203 #include "nearfield_map_base_pa_node.hxx"
204 
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
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
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


nearfield_map
Author(s):
autogenerated on Sat Feb 27 2021 03:09:46