46 #ifndef __PCD_FILTER_PA_ROS_H 47 #define __PCD_FILTER_PA_ROS_H 58 #include <sensor_msgs/PointCloud2.h> 59 #include <sensor_msgs/PointCloud.h> 60 #include <sensor_msgs/LaserScan.h> 65 #include <opencv2/highgui/highgui.hpp> 82 const sensor_msgs::PointCloudConstPtr &msg)
const;
86 const sensor_msgs::LaserScanConstPtr &msg)
const;
91 const std::string base_frame,
99 bool filterCloud(
const sensor_msgs::PointCloud2ConstPtr &msg,
100 sensor_msgs::PointCloud2Ptr &result);
103 bool filterCloud(sensor_msgs::PointCloud2Ptr &result);
110 const sensor_msgs::PointCloud2ConstPtr &msg,
111 const bool force_copy =
false)
const;
117 const sensor_msgs::PointCloud2ConstPtr cloud,
118 const std::vector<bool> mask)
const;
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
sensor_msgs::PointCloud2Ptr applyMasktoCloud(const sensor_msgs::PointCloud2ConstPtr cloud, const std::vector< bool > mask) const