Public Member Functions | Public Attributes | List of all members
cPcdFilterPaRos Class Reference

#include <pcdfilter_pa_ros.h>

Inheritance diagram for cPcdFilterPaRos:
Inheritance graph
[legend]

Public Member Functions

sensor_msgs::PointCloud2Ptr applyMasktoCloud (const sensor_msgs::PointCloud2ConstPtr cloud, const std::vector< bool > mask) const
 
sensor_msgs::PointCloud2Ptr convertCloud (const sensor_msgs::PointCloudConstPtr &msg) const
 converts the given pointcloud to newer format More...
 
sensor_msgs::PointCloud2Ptr convertCloud (const sensor_msgs::LaserScanConstPtr &msg) const
 converts the given laserscan to a pointcloud More...
 
const cv::Mat convertCloudToOpencv (const sensor_msgs::PointCloud2ConstPtr &msg, const bool force_copy=false) const
 
 cPcdFilterPaRos ()
 default constructor More...
 
bool filterCloud (const sensor_msgs::PointCloud2ConstPtr &msg, sensor_msgs::PointCloud2Ptr &result)
 filters the given pointcloud More...
 
bool filterCloud (sensor_msgs::PointCloud2Ptr &result)
 filters the buffered pointcloud More...
 
bool updateTf (const tf::TransformListener &tf_listener, const std::string base_frame, const ros::Time time=ros::Time::now())
 
bool updateTf (const tf::TransformListener &tf_listener)
 
 ~cPcdFilterPaRos ()
 default destructor More...
 
- Public Member Functions inherited from cPcdFilterPa
 cPcdFilterPa ()
 default constructor More...
 
std::vector< int > pointcloudFilter (const cv::Mat &pointcloud, std::vector< bool > &mask) const
 
 ~cPcdFilterPa ()
 default destructor More...
 

Public Attributes

cPcdFilterPaRosFilters filters_
 object for filter handling More...
 
cPcdFilterPaRosThrottle input_throttle_
 object for input throttling - e.g. only every 5th pointcloud More...
 
sensor_msgs::PointCloud2ConstPtr pcd_buffered_msg_
 
cv::Mat pcd_buffered_points_
 
cPcdFilterPaRosParameter rosparams_
 ros specific parameter More...
 
- Public Attributes inherited from cPcdFilterPa
cPcdFilterPaParameter params_
 specific parameter More...
 

Detailed Description

Definition at line 71 of file pcdfilter_pa_ros.h.

Constructor & Destructor Documentation

cPcdFilterPaRos::cPcdFilterPaRos ( )

default constructor

Definition at line 54 of file pcdfilter_pa_ros.cpp.

cPcdFilterPaRos::~cPcdFilterPaRos ( )

default destructor

Definition at line 58 of file pcdfilter_pa_ros.cpp.

Member Function Documentation

sensor_msgs::PointCloud2Ptr cPcdFilterPaRos::applyMasktoCloud ( const sensor_msgs::PointCloud2ConstPtr  cloud,
const std::vector< bool >  mask 
) const

internal function applys the mask to the pointcloud and creates a new pointcloud to store the results

Definition at line 313 of file pcdfilter_pa_ros.cpp.

sensor_msgs::PointCloud2Ptr cPcdFilterPaRos::convertCloud ( const sensor_msgs::PointCloudConstPtr msg) const

converts the given pointcloud to newer format

Definition at line 62 of file pcdfilter_pa_ros.cpp.

sensor_msgs::PointCloud2Ptr cPcdFilterPaRos::convertCloud ( const sensor_msgs::LaserScanConstPtr &  msg) const

converts the given laserscan to a pointcloud

Definition at line 72 of file pcdfilter_pa_ros.cpp.

const cv::Mat cPcdFilterPaRos::convertCloudToOpencv ( const sensor_msgs::PointCloud2ConstPtr &  msg,
const bool  force_copy = false 
) const

internal function extracts the x,y and z coordinates to opencv matrix of float if force_copy is set the returned matrix is never pointing to the original pointcloud message

Definition at line 190 of file pcdfilter_pa_ros.cpp.

bool cPcdFilterPaRos::filterCloud ( const sensor_msgs::PointCloud2ConstPtr &  msg,
sensor_msgs::PointCloud2Ptr &  result 
)

filters the given pointcloud

Definition at line 130 of file pcdfilter_pa_ros.cpp.

bool cPcdFilterPaRos::filterCloud ( sensor_msgs::PointCloud2Ptr &  result)

filters the buffered pointcloud

Definition at line 158 of file pcdfilter_pa_ros.cpp.

bool cPcdFilterPaRos::updateTf ( const tf::TransformListener tf_listener,
const std::string  base_frame,
const ros::Time  time = ros::Time::now() 
)

updates the internal transformations this should be done for each pointcloud

Definition at line 100 of file pcdfilter_pa_ros.cpp.

bool cPcdFilterPaRos::updateTf ( const tf::TransformListener tf_listener)

updates the internal transformations for a buffered pointcloud this should be done for each pointcloud

Definition at line 118 of file pcdfilter_pa_ros.cpp.

Member Data Documentation

cPcdFilterPaRosFilters cPcdFilterPaRos::filters_

object for filter handling

Definition at line 125 of file pcdfilter_pa_ros.h.

cPcdFilterPaRosThrottle cPcdFilterPaRos::input_throttle_

object for input throttling - e.g. only every 5th pointcloud

Definition at line 122 of file pcdfilter_pa_ros.h.

sensor_msgs::PointCloud2ConstPtr cPcdFilterPaRos::pcd_buffered_msg_

frame id of last pointcloud (usage depends on flag rosparams_.buffered_pointcloud)

Definition at line 135 of file pcdfilter_pa_ros.h.

cv::Mat cPcdFilterPaRos::pcd_buffered_points_

buffered pointcloud (usage depends on flag rosparams_.buffered_pointcloud)

Definition at line 132 of file pcdfilter_pa_ros.h.

cPcdFilterPaRosParameter cPcdFilterPaRos::rosparams_

ros specific parameter

Definition at line 128 of file pcdfilter_pa_ros.h.


The documentation for this class was generated from the following files:


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