pcdfilter_pa_node.h
Go to the documentation of this file.
1 /******************************************************************************
2 * *
3 * pcdfilter_pa_node.h *
4 * =================== *
5 * *
6 *******************************************************************************
7 * *
8 * github repository *
9 * https://github.com/TUC-ProAut/ros_pcdfilter *
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-2018, 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 __PCD_FILTER_PA_NODE_H
47 #define __PCD_FILTER_PA_NODE_H
48 
49 // local headers
52 #include "pcdfilter_pa/PcdFilterPaFilter.h"
53 #include "pcdfilter_pa/PcdFilterPaCloud.h"
54 
55 // ros headers
56 #include <ros/ros.h>
57 
58 #include <sensor_msgs/PointCloud2.h>
59 #include <sensor_msgs/PointCloud.h>
60 #include <sensor_msgs/LaserScan.h>
61 #include <std_srvs/Empty.h>
62 
63 #include <tf/transform_listener.h>
64 
65 // standard headers
66 #include <string>
67 #include <vector>
68 
69 //**************************[main]*********************************************
70 int main(int argc, char **argv);
71 
72 //**************************[cPcdFilterPaNode]*********************************
74  public:
77 
80 
81  protected:
84 
87 
90 
97 
100 
103 
108 
113 
115  void setCloudCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg);
117  void setCloudOldCallbackSub(const sensor_msgs::PointCloudConstPtr &msg);
119  void setCloudLaserCallbackSub(const sensor_msgs::LaserScanConstPtr &msg);
120 
122  bool filterCallbackSrv(
123  pcdfilter_pa::PcdFilterPaCloud::Request &req,
124  pcdfilter_pa::PcdFilterPaCloud::Response &res);
125 
128  pcdfilter_pa::PcdFilterPaFilter::Request &req,
129  pcdfilter_pa::PcdFilterPaFilter::Response &res);
132  pcdfilter_pa::PcdFilterPaFilter::Request &req,
133  pcdfilter_pa::PcdFilterPaFilter::Response &res);
134 
136  bool enableCallbackSrv(std_srvs::Empty::Request &req,
137  std_srvs::Empty::Response &res);
139  bool disableCallbackSrv(std_srvs::Empty::Request &req,
140  std_srvs::Empty::Response &res);
141 
143  void addFilters(const std::vector<std::string> &new_filters);
144 
145  private:
147  void enable(void);
149  void disable(void);
150 };
151 
152 #endif // __PCD_FILTER_PA_NODE_H
void addFilters(const std::vector< std::string > &new_filters)
function for adding several filters and giving feedback
void disable(void)
function for deactivating this node (disabling inputs)
ros::ServiceServer ser_add_filters_
service for adding additional filters
ros::ServiceServer ser_filter_
service for filtering
bool enableCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
callback function for enabling filter node
tf::TransformListener tf_listener_
for getting all necessary tfs
ros::Subscriber sub_pcd_old_
subscriber for a pointcloud (old format)
int main(int argc, char **argv)
bool changeFiltersCallbackSrv(pcdfilter_pa::PcdFilterPaFilter::Request &req, pcdfilter_pa::PcdFilterPaFilter::Response &res)
callback function for changing filters
ros::ServiceServer ser_enable_
service for enabling node
bool addFiltersCallbackSrv(pcdfilter_pa::PcdFilterPaFilter::Request &req, pcdfilter_pa::PcdFilterPaFilter::Response &res)
callback function for adding additional filters
cPcdFilterPaNode()
default constructor
void enable(void)
function for activating this node (enabling inputs)
ros::Subscriber sub_laser_
subscriber for a laserscan
ros::Subscriber sub_pcd_
subscriber for a pointcloud
void setCloudLaserCallbackSub(const sensor_msgs::LaserScanConstPtr &msg)
callback function for receiving a laserscan
~cPcdFilterPaNode()
default destructor
ros::NodeHandle nh_
node handler for topic subscription and advertising
cPcdFilterPaNodeParameter nodeparams_
ros specific variables, which will be read from Parameterserver
bool disableCallbackSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
callback function for disabling filter node
void setCloudCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a pointcloud
ros::Publisher pub_pcd_
publisher for filtered pointcloud
bool filterCallbackSrv(pcdfilter_pa::PcdFilterPaCloud::Request &req, pcdfilter_pa::PcdFilterPaCloud::Response &res)
callback function for filtering via service
ros::ServiceServer ser_change_filters_
service for changing filters
ros::ServiceServer ser_disable_
service for disabling node
void setCloudOldCallbackSub(const sensor_msgs::PointCloudConstPtr &msg)
callback function for receiving a pointcloud (old format)


pcdfilter_pa
Author(s):
autogenerated on Fri Jun 7 2019 21:53:31