$search

robot_self_filter::SelfMask< tpCloudType > Class Template 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 tpCloudType &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 tpCloudType &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 tpCloudType &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 tpCloudType &data_in, std::vector< int > &mask)
 Perform the actual mask computation.
void maskAuxIntersection (const tpCloudType &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

template<typename tpCloudType>
class robot_self_filter::SelfMask< tpCloudType >

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

Definition at line 63 of file self_mask.h.


Constructor & Destructor Documentation

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

Construct the filter.

Definition at line 92 of file self_mask.h.

template<typename tpCloudType>
robot_self_filter::SelfMask< tpCloudType >::~SelfMask ( void   )  [inline]

Destructor to clean up.

Definition at line 98 of file self_mask.h.


Member Function Documentation

template<typename tpCloudType>
void robot_self_filter::SelfMask< tpCloudType >::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).

template<typename tpCloudType>
void robot_self_filter::SelfMask< tpCloudType >::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.

template<typename tpCloudType>
void robot_self_filter::SelfMask< tpCloudType >::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.

template<typename tpCloudType>
void robot_self_filter::SelfMask< tpCloudType >::computeBoundingSpheres ( void   )  [private]

Compute bounding spheres for the checked robot links.

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

Configure the filter.

template<typename tpCloudType>
void robot_self_filter::SelfMask< tpCloudType >::freeMemory ( void   )  [private]

Free memory.

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

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

template<typename tpCloudType>
int robot_self_filter::SelfMask< tpCloudType >::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.

template<typename tpCloudType>
int robot_self_filter::SelfMask< tpCloudType >::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.

template<typename tpCloudType>
int robot_self_filter::SelfMask< tpCloudType >::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.

template<typename tpCloudType>
int robot_self_filter::SelfMask< tpCloudType >::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.

template<typename tpCloudType>
void robot_self_filter::SelfMask< tpCloudType >::maskAuxContainment ( const tpCloudType &  data_in,
std::vector< int > &  mask 
) [private]

Perform the actual mask computation.

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

Perform the actual mask computation.

template<typename tpCloudType>
void robot_self_filter::SelfMask< tpCloudType >::maskContainment ( const tpCloudType &  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.

template<typename tpCloudType>
void robot_self_filter::SelfMask< tpCloudType >::maskIntersection ( const tpCloudType &  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.

template<typename tpCloudType>
void robot_self_filter::SelfMask< tpCloudType >::maskIntersection ( const tpCloudType &  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.


Member Data Documentation

template<typename tpCloudType>
std::vector<SeeLink> robot_self_filter::SelfMask< tpCloudType >::bodies_ [private]

Definition at line 184 of file self_mask.h.

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

Definition at line 186 of file self_mask.h.

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

Definition at line 185 of file self_mask.h.

template<typename tpCloudType>
double robot_self_filter::SelfMask< tpCloudType >::min_sensor_dist_ [private]

Definition at line 182 of file self_mask.h.

template<typename tpCloudType>
ros::NodeHandle robot_self_filter::SelfMask< tpCloudType >::nh_ [private]

Definition at line 179 of file self_mask.h.

template<typename tpCloudType>
btVector3 robot_self_filter::SelfMask< tpCloudType >::sensor_pos_ [private]

Definition at line 181 of file self_mask.h.

template<typename tpCloudType>
tf::TransformListener& robot_self_filter::SelfMask< tpCloudType >::tf_ [private]

Definition at line 178 of file self_mask.h.


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


srs_env_model_utils
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Sun Dec 23 12:34:30 2012