Computing a mask for a pointcloud that states which points are inside the robot.
More...
|
void | assumeFrame (const std_msgs::Header &header) |
| Assume subsequent calls to getMaskX() will be in the frame passed to this function. The frame in which the sensor is located is optional. More...
|
|
void | assumeFrame (const std_msgs::Header &header, 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) More...
|
|
void | assumeFrame (const std_msgs::Header &header, 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. More...
|
|
void | getLinkNames (std::vector< std::string > &frames) const |
| Get the set of link names that have been instantiated for self filtering. More...
|
|
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. More...
|
|
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. More...
|
|
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. More...
|
|
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. More...
|
|
void | maskContainment (const PointCloud &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. More...
|
|
void | maskIntersection (const PointCloud &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. More...
|
|
void | maskIntersection (const PointCloud &data_in, const tf::Vector3 &sensor_pos, 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. More...
|
|
| SelfMask (tf::TransformListener &tf, const std::vector< LinkInfo > &links) |
| Construct the filter. More...
|
|
| ~SelfMask (void) |
| Destructor to clean up. More...
|
|
template<typename PointT>
class robot_self_filter::SelfMask< PointT >
Computing a mask for a pointcloud that states which points are inside the robot.
Definition at line 145 of file self_mask.h.
template<typename PointT>
void robot_self_filter::SelfMask< PointT >::maskIntersection |
( |
const PointCloud & |
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 |
|
) |
| |
|
inline |
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 213 of file self_mask.h.
template<typename PointT>
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 239 of file self_mask.h.