Classes | Public Member Functions | Private Member Functions | Private Attributes
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)
 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, 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, const tf::Vector3 &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 getLinkNames (std::vector< std::string > &frames) const
 Get the set of link names that have been instantiated for self filtering.
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 getMaskContainment (const tf::Vector3 &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 getMaskIntersection (double x, double y, double z, const boost::function< void(const tf::Vector3 &)> &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 (const tf::Vector3 &pt, const boost::function< void(const tf::Vector3 &)> &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 std::string &sensor_frame, const double min_sensor_dist, std::vector< int > &mask, const boost::function< void(const tf::Vector3 &)> &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.
void maskIntersection (const pcl::PointCloud< pcl::PointXYZ > &data_in, const tf::Vector3 &sensor, const double min_sensor_dist, std::vector< int > &mask, const boost::function< void(const tf::Vector3 &)> &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.
 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 tf::Vector3 &)> &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_
tf::Vector3 sensor_pos_
tf::TransformListenertf_

Detailed Description

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

Definition at line 61 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 90 of file self_mask.h.

Destructor to clean up.

Definition at line 96 of file self_mask.h.


Member Function Documentation

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 303 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 276 of file self_mask.cpp.

void robot_self_filter::SelfMask::assumeFrame ( const std::string &  frame_id,
const ros::Time stamp,
const tf::Vector3 &  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 269 of file self_mask.cpp.

Compute bounding spheres for the checked robot links.

Definition at line 259 of file self_mask.cpp.

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

Configure the filter.

Definition at line 115 of file self_mask.cpp.

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

Free memory.

Definition at line 49 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 211 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 445 of file self_mask.cpp.

int robot_self_filter::SelfMask::getMaskContainment ( const tf::Vector3 &  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 435 of file self_mask.cpp.

int robot_self_filter::SelfMask::getMaskIntersection ( double  x,
double  y,
double  z,
const boost::function< void(const tf::Vector3 &)> &  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 493 of file self_mask.cpp.

int robot_self_filter::SelfMask::getMaskIntersection ( const tf::Vector3 &  pt,
const boost::function< void(const tf::Vector3 &)> &  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 450 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 335 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 tf::Vector3 &)> &  callback 
) [private]

Perform the actual mask computation.

Definition at line 360 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 217 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 tf::Vector3 &)> &  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 229 of file self_mask.cpp.

void robot_self_filter::SelfMask::maskIntersection ( const pcl::PointCloud< pcl::PointXYZ > &  data_in,
const tf::Vector3 &  sensor,
const double  min_sensor_dist,
std::vector< int > &  mask,
const boost::function< void(const tf::Vector3 &)> &  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 246 of file self_mask.cpp.


Member Data Documentation

Definition at line 182 of file self_mask.h.

Definition at line 184 of file self_mask.h.

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

Definition at line 183 of file self_mask.h.

Definition at line 180 of file self_mask.h.

Definition at line 177 of file self_mask.h.

Definition at line 179 of file self_mask.h.

Definition at line 176 of file self_mask.h.


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


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