Public Types | Public Member Functions | Protected Attributes | List of all members
filters::SelfFilter< PointT > 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< PointT >:
Inheritance graph
[legend]

Public Types

typedef pcl::PointCloud< PointT > PointCloud
 

Public Member Functions

virtual bool configure (void)
 
void fillDiff (const PointCloud &data_in, const std::vector< int > &keep, PointCloud &data_out)
 
void fillResult (const PointCloud &data_in, const std::vector< int > &keep, PointCloud &data_out)
 
robot_self_filter::SelfMask< PointT > * getSelfMask ()
 
 SelfFilter (ros::NodeHandle nh)
 Construct the filter. More...
 
void setSensorFrame (const std::string &frame)
 
virtual bool update (const PointCloud &data_in, PointCloud &data_out)
 Update the filter and return the data seperately. More...
 
virtual bool update (const PointCloud &data_in, PointCloud &data_out, PointCloud &data_diff)
 Update the filter and return the data seperately. More...
 
virtual bool update (const std::vector< PointCloud > &data_in, std::vector< PointCloud > &data_out)
 
bool updateWithSensorFrame (const PointCloud &data_in, PointCloud &data_out, const std::string &sensor_frame)
 
bool updateWithSensorFrame (const PointCloud &data_in, PointCloud &data_out, PointCloud &data_diff, const std::string &sensor_frame)
 
virtual bool updateWithSensorFrame (const std::vector< PointCloud > &data_in, std::vector< PointCloud > &data_out, const std::string &sensor_frame)
 
virtual ~SelfFilter (void)
 Destructor to clean up. More...
 
- Public Member Functions inherited from filters::FilterBase< pcl::PointCloud< PointT > >
bool configure (const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
 
bool configure (XmlRpc::XmlRpcValue &config)
 
 FilterBase ()
 
const std::string & getName ()
 
std::string getType ()
 
virtual bool update (const pcl::PointCloud< PointT > &data_in, pcl::PointCloud< PointT > &data_out)=0
 
virtual ~FilterBase ()
 

Protected Attributes

bool invert_
 
bool keep_organized_
 
double min_sensor_dist_
 
ros::NodeHandle nh_
 
std::string sensor_frame_
 
robot_self_filter::SelfMask< PointT > * sm_
 
tf::TransformListener tf_
 
- Protected Attributes inherited from filters::FilterBase< pcl::PointCloud< PointT > >
bool configured_
 
std::string filter_name_
 
std::string filter_type_
 
string_map_t params_
 

Additional Inherited Members

- Protected Member Functions inherited from filters::FilterBase< pcl::PointCloud< PointT > >
bool getParam (const std::string &name, std::string &value)
 
bool getParam (const std::string &name, XmlRpc::XmlRpcValue &value)
 
bool getParam (const std::string &name, double &value)
 
bool getParam (const std::string &name, std::vector< double > &value)
 
bool getParam (const std::string &name, unsigned int &value)
 
bool getParam (const std::string &name, int &value)
 
bool getParam (const std::string &name, std::vector< std::string > &value)
 
bool getParam (const std::string &name, bool &value)
 
bool loadConfiguration (XmlRpc::XmlRpcValue &config)
 

Detailed Description

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

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

Definition at line 45 of file self_see_filter.h.

Member Typedef Documentation

template<typename PointT>
typedef pcl::PointCloud<PointT> filters::SelfFilter< PointT >::PointCloud

Definition at line 49 of file self_see_filter.h.

Constructor & Destructor Documentation

template<typename PointT>
filters::SelfFilter< PointT >::SelfFilter ( ros::NodeHandle  nh)
inline

Construct the filter.

Definition at line 51 of file self_see_filter.h.

template<typename PointT>
virtual filters::SelfFilter< PointT >::~SelfFilter ( void  )
inlinevirtual

Destructor to clean up.

Definition at line 111 of file self_see_filter.h.

Member Function Documentation

template<typename PointT>
virtual bool filters::SelfFilter< PointT >::configure ( void  )
inlinevirtual
template<typename PointT>
void filters::SelfFilter< PointT >::fillDiff ( const PointCloud data_in,
const std::vector< int > &  keep,
PointCloud data_out 
)
inline

Definition at line 173 of file self_see_filter.h.

template<typename PointT>
void filters::SelfFilter< PointT >::fillResult ( const PointCloud data_in,
const std::vector< int > &  keep,
PointCloud data_out 
)
inline

Definition at line 192 of file self_see_filter.h.

template<typename PointT>
robot_self_filter::SelfMask<PointT>* filters::SelfFilter< PointT >::getSelfMask ( )
inline

Definition at line 238 of file self_see_filter.h.

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

Definition at line 242 of file self_see_filter.h.

template<typename PointT>
virtual bool filters::SelfFilter< PointT >::update ( const PointCloud data_in,
PointCloud data_out 
)
inlinevirtual

Update the filter and return the data seperately.

Parameters
data_inT array with length width
data_outT array with length width

Definition at line 138 of file self_see_filter.h.

template<typename PointT>
virtual bool filters::SelfFilter< PointT >::update ( const PointCloud data_in,
PointCloud data_out,
PointCloud data_diff 
)
inlinevirtual

Update the filter and return the data seperately.

Parameters
data_inT array with length width
data_outT array with length width

Definition at line 160 of file self_see_filter.h.

template<typename PointT>
virtual bool filters::SelfFilter< PointT >::update ( const std::vector< PointCloud > &  data_in,
std::vector< PointCloud > &  data_out 
)
inlinevirtual

Definition at line 228 of file self_see_filter.h.

template<typename PointT>
bool filters::SelfFilter< PointT >::updateWithSensorFrame ( const PointCloud data_in,
PointCloud data_out,
const std::string &  sensor_frame 
)
inline

Definition at line 128 of file self_see_filter.h.

template<typename PointT>
bool filters::SelfFilter< PointT >::updateWithSensorFrame ( const PointCloud data_in,
PointCloud data_out,
PointCloud data_diff,
const std::string &  sensor_frame 
)
inline

Definition at line 150 of file self_see_filter.h.

template<typename PointT>
virtual bool filters::SelfFilter< PointT >::updateWithSensorFrame ( const std::vector< PointCloud > &  data_in,
std::vector< PointCloud > &  data_out,
const std::string &  sensor_frame 
)
inlinevirtual

Definition at line 222 of file self_see_filter.h.

Member Data Documentation

template<typename PointT>
bool filters::SelfFilter< PointT >::invert_
protected

Definition at line 252 of file self_see_filter.h.

template<typename PointT>
bool filters::SelfFilter< PointT >::keep_organized_
protected

Definition at line 255 of file self_see_filter.h.

template<typename PointT>
double filters::SelfFilter< PointT >::min_sensor_dist_
protected

Definition at line 254 of file self_see_filter.h.

template<typename PointT>
ros::NodeHandle filters::SelfFilter< PointT >::nh_
protected

Definition at line 251 of file self_see_filter.h.

template<typename PointT>
std::string filters::SelfFilter< PointT >::sensor_frame_
protected

Definition at line 253 of file self_see_filter.h.

template<typename PointT>
robot_self_filter::SelfMask<PointT>* filters::SelfFilter< PointT >::sm_
protected

Definition at line 249 of file self_see_filter.h.

template<typename PointT>
tf::TransformListener filters::SelfFilter< PointT >::tf_
protected

Definition at line 248 of file self_see_filter.h.


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


pr2_navigation_self_filter
Author(s): Eitan Marder-Eppstein
autogenerated on Mon Jun 10 2019 14:28:54