Public Member Functions | Protected Attributes
filters::SelfFilter< T > Class Template Reference

A filter to remove parts of the robot seen in a pointcloud. More...

#include <self_see_filter.h>

Inheritance diagram for filters::SelfFilter< T >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool configure (void)
void fillDiff (const pcl::PointCloud< pcl::PointXYZ > &data_in, const std::vector< int > &keep, pcl::PointCloud< pcl::PointXYZ > &data_out)
void fillResult (const pcl::PointCloud< pcl::PointXYZ > &data_in, const std::vector< int > &keep, pcl::PointCloud< pcl::PointXYZ > &data_out)
robot_self_filter::SelfMaskgetSelfMask ()
 SelfFilter (ros::NodeHandle nh)
 Construct the filter.
void setSensorFrame (const std::string &frame)
virtual bool update (const pcl::PointCloud< pcl::PointXYZ > &data_in, pcl::PointCloud< pcl::PointXYZ > &data_out)
 Update the filter and return the data seperately.
virtual bool update (const pcl::PointCloud< pcl::PointXYZ > &data_in, pcl::PointCloud< pcl::PointXYZ > &data_out, pcl::PointCloud< pcl::PointXYZ > &data_diff)
 Update the filter and return the data seperately.
bool updateWithSensorFrame (const pcl::PointCloud< pcl::PointXYZ > &data_in, pcl::PointCloud< pcl::PointXYZ > &data_out, const std::string &sensor_frame)
bool updateWithSensorFrame (const pcl::PointCloud< pcl::PointXYZ > &data_in, pcl::PointCloud< pcl::PointXYZ > &data_out, pcl::PointCloud< pcl::PointXYZ > &data_diff, const std::string &sensor_frame)
virtual ~SelfFilter (void)
 Destructor to clean up.

Protected Attributes

std::string annotate_
bool invert_
double min_sensor_dist_
ros::NodeHandle nh_
std::string sensor_frame_
robot_self_filter::SelfMasksm_
tf::TransformListener tf_

Detailed Description

template<typename T>
class filters::SelfFilter< T >

A filter to remove parts of the robot seen in a pointcloud.

Definition at line 44 of file self_see_filter.h.


Constructor & Destructor Documentation

template<typename T>
filters::SelfFilter< T >::SelfFilter ( ros::NodeHandle  nh) [inline]

Construct the filter.

Definition at line 48 of file self_see_filter.h.

template<typename T>
virtual filters::SelfFilter< T >::~SelfFilter ( void  ) [inline, virtual]

Destructor to clean up.

Definition at line 127 of file self_see_filter.h.


Member Function Documentation

template<typename T>
virtual bool filters::SelfFilter< T >::configure ( void  ) [inline, virtual]

Implements filters::FilterBase< T >.

Definition at line 133 of file self_see_filter.h.

template<typename T>
void filters::SelfFilter< T >::fillDiff ( const pcl::PointCloud< pcl::PointXYZ > &  data_in,
const std::vector< int > &  keep,
pcl::PointCloud< pcl::PointXYZ > &  data_out 
) [inline]

Definition at line 198 of file self_see_filter.h.

template<typename T>
void filters::SelfFilter< T >::fillResult ( const pcl::PointCloud< pcl::PointXYZ > &  data_in,
const std::vector< int > &  keep,
pcl::PointCloud< pcl::PointXYZ > &  data_out 
) [inline]

Definition at line 227 of file self_see_filter.h.

template<typename T>
robot_self_filter::SelfMask* filters::SelfFilter< T >::getSelfMask ( ) [inline]

Definition at line 308 of file self_see_filter.h.

template<typename T>
void filters::SelfFilter< T >::setSensorFrame ( const std::string &  frame) [inline]

Definition at line 313 of file self_see_filter.h.

template<typename T>
virtual bool filters::SelfFilter< T >::update ( const pcl::PointCloud< pcl::PointXYZ > &  data_in,
pcl::PointCloud< pcl::PointXYZ > &  data_out 
) [inline, virtual]

Update the filter and return the data seperately.

Parameters:
data_inT array with length width
data_outT array with length width

Definition at line 157 of file self_see_filter.h.

template<typename T>
virtual bool filters::SelfFilter< T >::update ( const pcl::PointCloud< pcl::PointXYZ > &  data_in,
pcl::PointCloud< pcl::PointXYZ > &  data_out,
pcl::PointCloud< pcl::PointXYZ > &  data_diff 
) [inline, virtual]

Update the filter and return the data seperately.

Parameters:
data_inT array with length width
data_outT array with length width

Definition at line 182 of file self_see_filter.h.

template<typename T>
bool filters::SelfFilter< T >::updateWithSensorFrame ( const pcl::PointCloud< pcl::PointXYZ > &  data_in,
pcl::PointCloud< pcl::PointXYZ > &  data_out,
const std::string &  sensor_frame 
) [inline]

Definition at line 146 of file self_see_filter.h.

template<typename T>
bool filters::SelfFilter< T >::updateWithSensorFrame ( const pcl::PointCloud< pcl::PointXYZ > &  data_in,
pcl::PointCloud< pcl::PointXYZ > &  data_out,
pcl::PointCloud< pcl::PointXYZ > &  data_diff,
const std::string &  sensor_frame 
) [inline]

Definition at line 172 of file self_see_filter.h.


Member Data Documentation

template<typename T>
std::string filters::SelfFilter< T >::annotate_ [protected]

Definition at line 326 of file self_see_filter.h.

template<typename T>
bool filters::SelfFilter< T >::invert_ [protected]

Definition at line 324 of file self_see_filter.h.

template<typename T>
double filters::SelfFilter< T >::min_sensor_dist_ [protected]

Definition at line 327 of file self_see_filter.h.

template<typename T>
ros::NodeHandle filters::SelfFilter< T >::nh_ [protected]

Definition at line 323 of file self_see_filter.h.

template<typename T>
std::string filters::SelfFilter< T >::sensor_frame_ [protected]

Definition at line 325 of file self_see_filter.h.

template<typename T>
robot_self_filter::SelfMask* filters::SelfFilter< T >::sm_ [protected]

Definition at line 321 of file self_see_filter.h.

template<typename T>
tf::TransformListener filters::SelfFilter< T >::tf_ [protected]

Definition at line 320 of file self_see_filter.h.


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


robot_self_filter
Author(s): Ioan Sucan
autogenerated on Mon Dec 2 2013 12:33:58