pcdfilter_pa_ros.h
Go to the documentation of this file.
1 /******************************************************************************
2 * *
3 * pcdfilter_pa_ros.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_ROS_H
47 #define __PCD_FILTER_PA_ROS_H
48 
49 // local headers
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 
62 #include <tf/transform_datatypes.h>
63 
64 // additional libraries
65 #include <opencv2/highgui/highgui.hpp>
66 
67 // standard headers
68 #include <string>
69 
70 //**************************[cPcdFilterPaRos]**********************************
71 class cPcdFilterPaRos : public cPcdFilterPa {
72  public:
73 
76 
79 
81  sensor_msgs::PointCloud2Ptr convertCloud(
82  const sensor_msgs::PointCloudConstPtr &msg) const;
83 
85  sensor_msgs::PointCloud2Ptr convertCloud(
86  const sensor_msgs::LaserScanConstPtr &msg) const;
87 
90  bool updateTf( const tf::TransformListener &tf_listener,
91  const std::string base_frame,
92  const ros::Time time = ros::Time::now());
93 
96  bool updateTf( const tf::TransformListener &tf_listener);
97 
99  bool filterCloud(const sensor_msgs::PointCloud2ConstPtr &msg,
100  sensor_msgs::PointCloud2Ptr &result);
101 
103  bool filterCloud(sensor_msgs::PointCloud2Ptr &result);
104 
109  const cv::Mat convertCloudToOpencv(
110  const sensor_msgs::PointCloud2ConstPtr &msg,
111  const bool force_copy = false) const;
112 
116  sensor_msgs::PointCloud2Ptr applyMasktoCloud(
117  const sensor_msgs::PointCloud2ConstPtr cloud,
118  const std::vector<bool> mask) const;
119 
120 
123 
126 
129 
135  sensor_msgs::PointCloud2ConstPtr pcd_buffered_msg_;
136 
137 };
138 
139 
140 #endif // __PCD_FILTER_PA_ROS_H
cPcdFilterPaRosThrottle input_throttle_
object for input throttling - e.g. only every 5th pointcloud
cv::Mat pcd_buffered_points_
cPcdFilterPaRosParameter rosparams_
ros specific parameter
bool updateTf(const tf::TransformListener &tf_listener, const std::string base_frame, const ros::Time time=ros::Time::now())
sensor_msgs::PointCloud2Ptr convertCloud(const sensor_msgs::PointCloudConstPtr &msg) const
converts the given pointcloud to newer format
cPcdFilterPaRosFilters filters_
object for filter handling
const cv::Mat convertCloudToOpencv(const sensor_msgs::PointCloud2ConstPtr &msg, const bool force_copy=false) const
sensor_msgs::PointCloud2ConstPtr pcd_buffered_msg_
bool filterCloud(const sensor_msgs::PointCloud2ConstPtr &msg, sensor_msgs::PointCloud2Ptr &result)
filters the given pointcloud
~cPcdFilterPaRos()
default destructor
cPcdFilterPaRos()
default constructor
static Time now()
sensor_msgs::PointCloud2Ptr applyMasktoCloud(const sensor_msgs::PointCloud2ConstPtr cloud, const std::vector< bool > mask) const


pcdfilter_pa
Author(s):
autogenerated on Mon Dec 23 2019 03:56:23