robot_self_filter::SelfMask Class Reference

Computing a mask for a pointcloud that states which points are inside the robot. More...

#include <self_mask.h>

List of all members.

Classes

struct  SeeLink
struct  SortBodies

Public Member Functions

void assumeFrame (const std::string &frame_id, const ros::Time &stamp, const btVector3 &sensor_pos, const double min_sensor_dist)
 Assume subsequent calls to getMaskX() will be in the frame passed to this function. Also specify which possition to assume for the sensor (frame is not needed).
void assumeFrame (const std::string &frame_id, const ros::Time &stamp, const std::string &sensor_frame, const double min_sensor_dist)
 Assume subsequent calls to getMaskX() will be in the frame passed to this function. The frame in which the sensor is located is optional.
void assumeFrame (const std::string &frame_id, const ros::Time &stamp)
 Assume subsequent calls to getMaskX() will be in the frame passed to this function. The frame in which the sensor is located is optional.
void getLinkNames (std::vector< std::string > &frames) const
 Get the set of link names that have been instantiated for self filtering.
int getMaskContainment (const btVector3 &pt) const
 Get the containment mask (INSIDE or OUTSIDE) value for an individual point. No setup is performed, assumeFrame() should be called before use.
int getMaskContainment (double x, double y, double z) const
 Get the containment mask (INSIDE or OUTSIDE) value for an individual point. No setup is performed, assumeFrame() should be called before use.
int getMaskIntersection (const btVector3 &pt, const boost::function< void(const btVector3 &)> &intersectionCallback=NULL) const
 Get the intersection mask (INSIDE, OUTSIDE or SHADOW) value for an individual point. No setup is performed, assumeFrame() should be called before use.
int getMaskIntersection (double x, double y, double z, const boost::function< void(const btVector3 &)> &intersectionCallback=NULL) const
 Get the intersection mask (INSIDE, OUTSIDE or SHADOW) value for an individual point. No setup is performed, assumeFrame() should be called before use.
void maskContainment (const pcl::PointCloud< pcl::PointXYZ > &data_in, std::vector< int > &mask)
 Compute the containment mask (INSIDE or OUTSIDE) for a given pointcloud. If a mask element is INSIDE, the point is inside the robot. The point is outside if the mask element is OUTSIDE.
void maskIntersection (const pcl::PointCloud< pcl::PointXYZ > &data_in, const btVector3 &sensor, const double min_sensor_dist, std::vector< int > &mask, const boost::function< void(const btVector3 &)> &intersectionCallback=NULL)
 Compute the intersection mask for a given pointcloud. If a mask element can have one of the values INSIDE, OUTSIDE or SHADOW. If the value is SHADOW, the point is on a ray behind the robot and should not have been seen. If the mask element is INSIDE, the point is inside the robot. The origin of the sensor is specified as well.
void maskIntersection (const pcl::PointCloud< pcl::PointXYZ > &data_in, const std::string &sensor_frame, const double min_sensor_dist, std::vector< int > &mask, const boost::function< void(const btVector3 &)> &intersectionCallback=NULL)
 Compute the intersection mask for a given pointcloud. If a mask element can have one of the values INSIDE, OUTSIDE or SHADOW. If the value is SHADOW, the point is on a ray behind the robot and should not have been seen. If the mask element is INSIDE, the point is inside the robot. The sensor frame is specified to obtain the origin of the sensor. A callback can be registered for the first intersection point on each body.
 SelfMask (tf::TransformListener &tf, const std::vector< LinkInfo > &links)
 Construct the filter.
 ~SelfMask (void)
 Destructor to clean up.

Private Member Functions

void computeBoundingSpheres (void)
 Compute bounding spheres for the checked robot links.
bool configure (const std::vector< LinkInfo > &links)
 Configure the filter.
void freeMemory (void)
 Free memory.
void maskAuxContainment (const pcl::PointCloud< pcl::PointXYZ > &data_in, std::vector< int > &mask)
 Perform the actual mask computation.
void maskAuxIntersection (const pcl::PointCloud< pcl::PointXYZ > &data_in, std::vector< int > &mask, const boost::function< void(const btVector3 &)> &callback)
 Perform the actual mask computation.

Private Attributes

std::vector< SeeLinkbodies_
std::vector
< bodies::BoundingSphere > 
bspheres_
std::vector< double > bspheresRadius2_
double min_sensor_dist_
ros::NodeHandle nh_
btVector3 sensor_pos_
tf::TransformListener & tf_

Detailed Description

Computing a mask for a pointcloud that states which points are inside the robot.

Definition at line 59 of file self_mask.h.


Constructor & Destructor Documentation

robot_self_filter::SelfMask::SelfMask ( tf::TransformListener &  tf,
const std::vector< LinkInfo > &  links 
) [inline]

Construct the filter.

Definition at line 88 of file self_mask.h.

robot_self_filter::SelfMask::~SelfMask ( void   )  [inline]

Destructor to clean up.

Definition at line 94 of file self_mask.h.


Member Function Documentation

void robot_self_filter::SelfMask::assumeFrame ( const std::string &  frame_id,
const ros::Time &  stamp,
const btVector3 &  sensor_pos,
const double  min_sensor_dist 
)

Assume subsequent calls to getMaskX() will be in the frame passed to this function. Also specify which possition to assume for the sensor (frame is not needed).

Definition at line 326 of file self_mask.cpp.

void robot_self_filter::SelfMask::assumeFrame ( const std::string &  frame_id,
const ros::Time &  stamp,
const std::string &  sensor_frame,
const double  min_sensor_dist 
)

Assume subsequent calls to getMaskX() will be in the frame passed to this function. The frame in which the sensor is located is optional.

Definition at line 333 of file self_mask.cpp.

void robot_self_filter::SelfMask::assumeFrame ( const std::string &  frame_id,
const ros::Time &  stamp 
)

Assume subsequent calls to getMaskX() will be in the frame passed to this function. The frame in which the sensor is located is optional.

Definition at line 360 of file self_mask.cpp.

void robot_self_filter::SelfMask::computeBoundingSpheres ( void   )  [private]

Compute bounding spheres for the checked robot links.

Definition at line 316 of file self_mask.cpp.

bool robot_self_filter::SelfMask::configure ( const std::vector< LinkInfo > &  links  )  [private]

Configure the filter.

Definition at line 172 of file self_mask.cpp.

void robot_self_filter::SelfMask::freeMemory ( void   )  [private]

Free memory.

Definition at line 42 of file self_mask.cpp.

void robot_self_filter::SelfMask::getLinkNames ( std::vector< std::string > &  frames  )  const

Get the set of link names that have been instantiated for self filtering.

Definition at line 268 of file self_mask.cpp.

int robot_self_filter::SelfMask::getMaskContainment ( const btVector3 &  pt  )  const

Get the containment mask (INSIDE or OUTSIDE) value for an individual point. No setup is performed, assumeFrame() should be called before use.

Definition at line 492 of file self_mask.cpp.

int robot_self_filter::SelfMask::getMaskContainment ( double  x,
double  y,
double  z 
) const

Get the containment mask (INSIDE or OUTSIDE) value for an individual point. No setup is performed, assumeFrame() should be called before use.

Definition at line 502 of file self_mask.cpp.

int robot_self_filter::SelfMask::getMaskIntersection ( const btVector3 &  pt,
const boost::function< void(const btVector3 &)> &  intersectionCallback = NULL 
) const

Get the intersection mask (INSIDE, OUTSIDE or SHADOW) value for an individual point. No setup is performed, assumeFrame() should be called before use.

Definition at line 507 of file self_mask.cpp.

int robot_self_filter::SelfMask::getMaskIntersection ( double  x,
double  y,
double  z,
const boost::function< void(const btVector3 &)> &  intersectionCallback = NULL 
) const

Get the intersection mask (INSIDE, OUTSIDE or SHADOW) value for an individual point. No setup is performed, assumeFrame() should be called before use.

Definition at line 550 of file self_mask.cpp.

void robot_self_filter::SelfMask::maskAuxContainment ( const pcl::PointCloud< pcl::PointXYZ > &  data_in,
std::vector< int > &  mask 
) [private]

Perform the actual mask computation.

Definition at line 392 of file self_mask.cpp.

void robot_self_filter::SelfMask::maskAuxIntersection ( const pcl::PointCloud< pcl::PointXYZ > &  data_in,
std::vector< int > &  mask,
const boost::function< void(const btVector3 &)> &  callback 
) [private]

Perform the actual mask computation.

Definition at line 417 of file self_mask.cpp.

void robot_self_filter::SelfMask::maskContainment ( const pcl::PointCloud< pcl::PointXYZ > &  data_in,
std::vector< int > &  mask 
)

Compute the containment mask (INSIDE or OUTSIDE) for a given pointcloud. If a mask element is INSIDE, the point is inside the robot. The point is outside if the mask element is OUTSIDE.

Definition at line 274 of file self_mask.cpp.

void robot_self_filter::SelfMask::maskIntersection ( const pcl::PointCloud< pcl::PointXYZ > &  data_in,
const btVector3 &  sensor,
const double  min_sensor_dist,
std::vector< int > &  mask,
const boost::function< void(const btVector3 &)> &  intersectionCallback = NULL 
)

Compute the intersection mask for a given pointcloud. If a mask element can have one of the values INSIDE, OUTSIDE or SHADOW. If the value is SHADOW, the point is on a ray behind the robot and should not have been seen. If the mask element is INSIDE, the point is inside the robot. The origin of the sensor is specified as well.

Definition at line 303 of file self_mask.cpp.

void robot_self_filter::SelfMask::maskIntersection ( const pcl::PointCloud< pcl::PointXYZ > &  data_in,
const std::string &  sensor_frame,
const double  min_sensor_dist,
std::vector< int > &  mask,
const boost::function< void(const btVector3 &)> &  intersectionCallback = NULL 
)

Compute the intersection mask for a given pointcloud. If a mask element can have one of the values INSIDE, OUTSIDE or SHADOW. If the value is SHADOW, the point is on a ray behind the robot and should not have been seen. If the mask element is INSIDE, the point is inside the robot. The sensor frame is specified to obtain the origin of the sensor. A callback can be registered for the first intersection point on each body.

Definition at line 286 of file self_mask.cpp.


Member Data Documentation

Definition at line 180 of file self_mask.h.

std::vector<bodies::BoundingSphere> robot_self_filter::SelfMask::bspheres_ [private]

Definition at line 182 of file self_mask.h.

std::vector<double> robot_self_filter::SelfMask::bspheresRadius2_ [private]

Definition at line 181 of file self_mask.h.

Definition at line 178 of file self_mask.h.

ros::NodeHandle robot_self_filter::SelfMask::nh_ [private]

Definition at line 175 of file self_mask.h.

Definition at line 177 of file self_mask.h.

tf::TransformListener& robot_self_filter::SelfMask::tf_ [private]

Definition at line 174 of file self_mask.h.


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


robot_self_filter
Author(s): Ioan Sucan
autogenerated on Fri Jan 11 09:10:39 2013