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 * 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 * Author: *
15 * Peter Weissig *
16 * *
17 *******************************************************************************
18 * *
19 * New BSD License *
20 * *
21 * Copyright (c) 2015-2021 TU Chemnitz *
22 * All rights reserved. *
23 * *
24 * Redistribution and use in source and binary forms, with or without *
25 * modification, are permitted provided that the following conditions are met: *
26 * * Redistributions of source code must retain the above copyright notice, *
27 * this list of conditions and the following disclaimer. *
28 * * Redistributions in binary form must reproduce the above copyright *
29 * notice, this list of conditions and the following disclaimer in the *
30 * documentation and/or other materials provided with the distribution. *
31 * * Neither the name of the copyright holder nor the names of its *
32 * contributors may be used to endorse or promote products derived from *
33 * this software without specific prior written permission. *
34 * *
35 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS *
36 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED *
37 * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR *
38 * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR *
39 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, *
40 * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, *
41 * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; *
42 * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, *
43 * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR *
44 * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF *
45 * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *
46 * *
47 ******************************************************************************/
48 
49 #ifndef __NEARFIELD_MAP_BASE_PA_NODE_H
50 #define __NEARFIELD_MAP_BASE_PA_NODE_H
51 
52 // local headers
54 
55 #include "nearfield_map/NearfieldMapFileName.h"
56 #include "nearfield_map/NearfieldMapGetSize.h"
57 #include "nearfield_map/NearfieldMapChangeSettings.h"
58 #include "nearfield_map/NearfieldMapRequest.h"
59 
60 // ros headers
61 #include <ros/ros.h>
62 
63 #include <std_msgs/Empty.h>
64 #include <std_msgs/Header.h>
65 //#include <geometry_msgs/Point.h>
66 #include <sensor_msgs/PointCloud2.h>
67 //#include <nav_msgs/Path.h>
68 #include <std_srvs/Empty.h>
69 
70 #include <tf/transform_listener.h>
71 
72 #include <octomap_msgs/Octomap.h>
73 
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>
78 
79 
80 // standard headers
81 #include <string>
82 #include <vector>
83 
84 //**************************[cNearfieldMapBasePaNode]**************************
85 template <typename NEARFIELDMAP>
86  class cNearfieldMapBasePaNode : public NEARFIELDMAP {
87  public:
88 
89  typedef NEARFIELDMAP MapTypeBase;
91 
94 
97 
99  void publish(void);
100 
102  bool getNearfield(sensor_msgs::PointCloud2Ptr &msg);
103 
106  bool checkTF(const std_msgs::Header &header,
107  tf::StampedTransform &transform);
108 
109  void changeSettings(void);
110 
111  protected:
112 
115 
117  cAddCloudParameter params_addcloud_camera_;
119  cAddCloudParameter params_addcloud_laser_scan_;
121  cAddCloudParameter params_addcloud_laser_full_;
122 
123 
125  int count_camera_;
127  int count_laser_scan_;
129  int count_laser_full_;
130 
133 
136 
137  // output throttle for auto-update
138  cPcdFilterPaRosThrottle output_throttle_;
139 
140  // output filter
141  cPcdFilterPaRos output_filter_;
142 
149 
160 
161 
164  void clearCallbackSub(const std_msgs::EmptyConstPtr &msg);
165 
168  bool clearCallbackSrv(std_srvs::Empty::Request &req,
169  std_srvs::Empty::Response &res);
170 
174  nearfield_map::NearfieldMapGetSize::Request &req,
175  nearfield_map::NearfieldMapGetSize::Response &res);
176 
179  bool saveCallbackSrv(
180  nearfield_map::NearfieldMapFileName::Request &req,
181  nearfield_map::NearfieldMapFileName::Response &res);
185  nearfield_map::NearfieldMapFileName::Request &req,
186  nearfield_map::NearfieldMapFileName::Response &res);
187 
190  bool sendCallbackSrv(std_srvs::Empty::Request &req,
191  std_srvs::Empty::Response &res);
195  nearfield_map::NearfieldMapRequest::Request &req,
196  nearfield_map::NearfieldMapRequest::Response &res);
197 
201  nearfield_map::NearfieldMapChangeSettings::Request &req,
202  nearfield_map::NearfieldMapChangeSettings::Response &res);
203 
204 };
205 
206 #include "nearfield_map_base_pa_node.hxx"
207 
208 #endif // __NEARFIELD_MAP_BASE_PA_NODE_H
cNearfieldMapBasePaNode::pub_nearfield_
ros::Publisher pub_nearfield_
puplisher for requested nearfield map (pointcloud)
Definition: nearfield_map_base_pa_node.h:205
cNearfieldMapBasePaNode::sub_laser_full_
ros::Subscriber sub_laser_full_
subscriber for single laserscans
Definition: nearfield_map_base_pa_node.h:194
cNearfieldMapBasePaNode::pub_cloud_free_
ros::Publisher pub_cloud_free_
puplisher for free voxels as pointcloud
Definition: nearfield_map_base_pa_node.h:201
cNearfieldMapBasePaNode::tf_listener_
tf::TransformListener tf_listener_
transformation of different frames
Definition: nearfield_map_base_pa_node.h:181
cNearfieldMapBasePaNode::changeSettings
void changeSettings(void)
ros::Publisher
cNearfieldMapBasePaNode::srv_save_
ros::ServiceServer srv_save_
service for saving the octomap
Definition: nearfield_map_base_pa_node.h:224
cNearfieldMapBasePaNode::sub_camera_
ros::Subscriber sub_camera_
subscriber for depth images from camera
Definition: nearfield_map_base_pa_node.h:190
ros.h
cNearfieldMapBasePaNode::checkTF
bool checkTF(const std_msgs::Header &header, tf::StampedTransform &transform)
cNearfieldMapBasePaNode::srv_change_settings_
ros::ServiceServer srv_change_settings_
service for changing parameters of the nearfield map
Definition: nearfield_map_base_pa_node.h:245
cNearfieldMapBasePaNode::params_addcloud_camera_
cAddCloudParameter params_addcloud_camera_
parameter for insertion of depth images from camera
Definition: nearfield_map_base_pa_node.h:163
cNearfieldMapBasePaNode::srv_load_
ros::ServiceServer srv_load_
service for loading a octomap
Definition: nearfield_map_base_pa_node.h:229
cNearfieldMapBasePaNode::getSizeCallbackSrv
bool getSizeCallbackSrv(nearfield_map::NearfieldMapGetSize::Request &req, nearfield_map::NearfieldMapGetSize::Response &res)
cNearfieldMapBasePaNode::MapTypeFull
cNearfieldMapBasePaNode< NEARFIELDMAP > MapTypeFull
Definition: nearfield_map_base_pa_node.h:136
cNearfieldMapBasePaNode::count_camera_
int count_camera_
number of inserted depth images from camera (pointclouds)
Definition: nearfield_map_base_pa_node.h:171
cNearfieldMapBasePaNode::pub_octomap_
ros::Publisher pub_octomap_
puplisher for the octomap (binary data)
Definition: nearfield_map_base_pa_node.h:197
cNearfieldMapBasePaNode
Definition: nearfield_map_base_pa_node.h:86
cNearfieldMapBasePaNode::loadCallbackSrv
bool loadCallbackSrv(nearfield_map::NearfieldMapFileName::Request &req, nearfield_map::NearfieldMapFileName::Response &res)
cNearfieldMapBasePaNode::clearCallbackSrv
bool clearCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
tf::StampedTransform
cNearfieldMapBasePaNode::changeSettingsCallbackSrv
bool changeSettingsCallbackSrv(nearfield_map::NearfieldMapChangeSettings::Request &req, nearfield_map::NearfieldMapChangeSettings::Response &res)
cNearfieldMapBasePaNode::srv_request_
ros::ServiceServer srv_request_
service for requesting a nearfield map (pointcloud) via this service
Definition: nearfield_map_base_pa_node.h:239
ros::ServiceServer
cNearfieldMapBasePaNode::params_addcloud_laser_scan_
cAddCloudParameter params_addcloud_laser_scan_
parameter for insertion of single laserscans
Definition: nearfield_map_base_pa_node.h:165
cNearfieldMapBasePaNode::sendCallbackSrv
bool sendCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
cNearfieldMapBasePaNode::count_laser_full_
int count_laser_full_
number of inserted full laserscans (pointclouds)
Definition: nearfield_map_base_pa_node.h:175
cNearfieldMapBasePaNode::count_laser_scan_
int count_laser_scan_
number of inserted single laserscans
Definition: nearfield_map_base_pa_node.h:173
cNearfieldMapBasePaNode::cNearfieldMapBasePaNode
cNearfieldMapBasePaNode()
default constructor
cNearfieldMapBasePaNode::saveCallbackSrv
bool saveCallbackSrv(nearfield_map::NearfieldMapFileName::Request &req, nearfield_map::NearfieldMapFileName::Response &res)
cNearfieldMapBasePaNode::params_addcloud_laser_full_
cAddCloudParameter params_addcloud_laser_full_
parameter for insertion of full laserscans
Definition: nearfield_map_base_pa_node.h:167
cNearfieldMapBasePaNode::clearCallbackSub
void clearCallbackSub(const std_msgs::EmptyConstPtr &msg)
cNearfieldMapBasePaNode::requestCallbackSrv
bool requestCallbackSrv(nearfield_map::NearfieldMapRequest::Request &req, nearfield_map::NearfieldMapRequest::Response &res)
cNearfieldMapBasePaNode::sub_clear_
ros::Subscriber sub_clear_
subscriber for clearing the octomap
Definition: nearfield_map_base_pa_node.h:209
nearfield_map_pa_node_parameter.h
cNearfieldMapBasePaNode::~cNearfieldMapBasePaNode
~cNearfieldMapBasePaNode()
default destructor
cNearfieldMapBasePaNode::srv_getsize_
ros::ServiceServer srv_getsize_
service for receiving the size of the octomap
Definition: nearfield_map_base_pa_node.h:218
transform_listener.h
cNearfieldMapPaNodeParameter
Definition: nearfield_map_pa_node_parameter.h:56
cNearfieldMapBasePaNode::output_throttle_
cPcdFilterPaRosThrottle output_throttle_
Definition: nearfield_map_base_pa_node.h:184
cNearfieldMapBasePaNode::publish
void publish(void)
function for publishing all topics (nearfield map and debugging)
cNearfieldMapBasePaNode::getNearfield
bool getNearfield(sensor_msgs::PointCloud2Ptr &msg)
function for retrieving requested nearfield map as pointcloud
cNearfieldMapBasePaNode::output_filter_
cPcdFilterPaRos output_filter_
Definition: nearfield_map_base_pa_node.h:187
tf::TransformListener
cNearfieldMapBasePaNode::srv_clear_
ros::ServiceServer srv_clear_
service for clearing the octomap
Definition: nearfield_map_base_pa_node.h:213
header
const std::string header
cNearfieldMapBasePaNode::srv_send_
ros::ServiceServer srv_send_
service for requesting a nearfield map (pointcloud) via output topic
Definition: nearfield_map_base_pa_node.h:235
cNearfieldMapBasePaNode::MapTypeBase
NEARFIELDMAP MapTypeBase
Definition: nearfield_map_base_pa_node.h:135
cNearfieldMapBasePaNode::nh_
ros::NodeHandle nh_
node handler for topic subscription and advertising
Definition: nearfield_map_base_pa_node.h:178
cNearfieldMapBasePaNode::pub_octomap_full_
ros::Publisher pub_octomap_full_
puplisher for the octomap (full data)
Definition: nearfield_map_base_pa_node.h:199
ros::NodeHandle
ros::Subscriber
cNearfieldMapBasePaNode::nodeparams_
cNearfieldMapPaNodeParameter nodeparams_
parameters
Definition: nearfield_map_base_pa_node.h:160
cNearfieldMapBasePaNode::pub_cloud_occupied_
ros::Publisher pub_cloud_occupied_
puplisher for occupied voxels as pointcloud
Definition: nearfield_map_base_pa_node.h:203
cNearfieldMapBasePaNode::sub_laser_scan_
ros::Subscriber sub_laser_scan_
subscriber for a laserscan
Definition: nearfield_map_base_pa_node.h:192


nearfield_map
Author(s):
autogenerated on Wed Mar 2 2022 00:42:09