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 sensor_msgs::PointCloud &data_in, const std::vector< int > &keep, sensor_msgs::PointCloud &data_out)
void fillResult (const sensor_msgs::PointCloud &data_in, const std::vector< int > &keep, sensor_msgs::PointCloud &data_out)
robot_self_filter::SelfMaskgetSelfMask ()
 SelfFilter (ros::NodeHandle nh)
 Construct the filter.
void setSensorFrame (const std::string &frame)
virtual bool update (const std::vector< sensor_msgs::PointCloud > &data_in, std::vector< sensor_msgs::PointCloud > &data_out)
virtual bool update (const sensor_msgs::PointCloud &data_in, sensor_msgs::PointCloud &data_out, sensor_msgs::PointCloud &data_diff)
 Update the filter and return the data seperately.
virtual bool update (const sensor_msgs::PointCloud &data_in, sensor_msgs::PointCloud &data_out)
 Update the filter and return the data seperately.
virtual bool updateWithSensorFrame (const std::vector< sensor_msgs::PointCloud > &data_in, std::vector< sensor_msgs::PointCloud > &data_out, const std::string &sensor_frame)
bool updateWithSensorFrame (const sensor_msgs::PointCloud &data_in, sensor_msgs::PointCloud &data_out, sensor_msgs::PointCloud &data_diff, const std::string &sensor_frame)
bool updateWithSensorFrame (const sensor_msgs::PointCloud &data_in, sensor_msgs::PointCloud &data_out, 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 41 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 39 of file self_see_filter.h.

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

Destructor to clean up.

Definition at line 102 of file self_see_filter.h.


Member Function Documentation

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

Definition at line 107 of file self_see_filter.h.

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

Definition at line 164 of file self_see_filter.h.

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

Definition at line 193 of file self_see_filter.h.

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

Definition at line 274 of file self_see_filter.h.

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

Definition at line 278 of file self_see_filter.h.

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

Definition at line 264 of file self_see_filter.h.

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

Update the filter and return the data seperately.

Parameters:
data_in T array with length width
data_out T array with length width

Definition at line 151 of file self_see_filter.h.

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

Update the filter and return the data seperately.

Parameters:
data_in T array with length width
data_out T array with length width

Definition at line 129 of file self_see_filter.h.

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

Definition at line 258 of file self_see_filter.h.

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

Definition at line 141 of file self_see_filter.h.

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

Definition at line 119 of file self_see_filter.h.


Member Data Documentation

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

Definition at line 290 of file self_see_filter.h.

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

Definition at line 288 of file self_see_filter.h.

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

Definition at line 291 of file self_see_filter.h.

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

Definition at line 287 of file self_see_filter.h.

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

Definition at line 289 of file self_see_filter.h.

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

Definition at line 285 of file self_see_filter.h.

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

Definition at line 284 of file self_see_filter.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Enumerations Enumerator


pr2_navigation_self_filter
Author(s): Eitan Marder-Eppstein
autogenerated on Fri Jan 11 09:35:23 2013