Computing a mask for a pointcloud that states which points are inside the robot. More...
#include <shape_mask.h>
Classes | |
struct | SeeShape |
struct | SortBodies |
Public Types | |
enum | { INSIDE = 0, OUTSIDE = 1, CLIP = 2 } |
The possible values of a mask computed for a point. More... | |
typedef boost::function< bool(ShapeHandle, Eigen::Affine3d &)> | TransformCallback |
Public Member Functions | |
ShapeHandle | addShape (const shapes::ShapeConstPtr &shape, double scale=1.0, double padding=0.0) |
int | getMaskContainment (double x, double y, double z) const |
Get the containment mask (INSIDE or OUTSIDE) value for an individual point. It is assumed the point is in the frame corresponding to the TransformCallback. | |
int | getMaskContainment (const Eigen::Vector3d &pt) const |
Get the containment mask (INSIDE or OUTSIDE) value for an individual point. It is assumed the point is in the frame corresponding to the TransformCallback. | |
void | maskContainment (const sensor_msgs::PointCloud2 &data_in, const Eigen::Vector3d &sensor_pos, const double min_sensor_dist, const double max_sensor_dist, 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 | removeShape (ShapeHandle handle) |
void | setTransformCallback (const TransformCallback &transform_callback) |
ShapeMask (const TransformCallback &transform_callback=TransformCallback()) | |
Construct the filter. | |
~ShapeMask () | |
Destructor to clean up. | |
Private Member Functions | |
void | freeMemory () |
Free memory. | |
Private Attributes | |
std::set< SeeShape, SortBodies > | bodies_ |
std::vector < bodies::BoundingSphere > | bspheres_ |
ShapeHandle | min_handle_ |
ShapeHandle | next_handle_ |
boost::mutex | shapes_lock_ |
TransformCallback | transform_callback_ |
std::map< ShapeHandle, std::set< SeeShape, SortBodies > ::iterator > | used_handles_ |
Computing a mask for a pointcloud that states which points are inside the robot.
Definition at line 55 of file shape_mask.h.
typedef boost::function<bool(ShapeHandle, Eigen::Affine3d&)> point_containment_filter::ShapeMask::TransformCallback |
Definition at line 66 of file shape_mask.h.
anonymous enum |
The possible values of a mask computed for a point.
Definition at line 59 of file shape_mask.h.
point_containment_filter::ShapeMask::ShapeMask | ( | const TransformCallback & | transform_callback = TransformCallback() | ) |
Construct the filter.
Definition at line 42 of file shape_mask.cpp.
Destructor to clean up.
Definition at line 47 of file shape_mask.cpp.
point_containment_filter::ShapeHandle point_containment_filter::ShapeMask::addShape | ( | const shapes::ShapeConstPtr & | shape, |
double | scale = 1.0 , |
||
double | padding = 0.0 |
||
) |
Definition at line 65 of file shape_mask.cpp.
void point_containment_filter::ShapeMask::freeMemory | ( | ) | [private] |
Free memory.
Definition at line 52 of file shape_mask.cpp.
int point_containment_filter::ShapeMask::getMaskContainment | ( | double | x, |
double | y, | ||
double | z | ||
) | const |
Get the containment mask (INSIDE or OUTSIDE) value for an individual point. It is assumed the point is in the frame corresponding to the TransformCallback.
Definition at line 178 of file shape_mask.cpp.
int point_containment_filter::ShapeMask::getMaskContainment | ( | const Eigen::Vector3d & | pt | ) | const |
Get the containment mask (INSIDE or OUTSIDE) value for an individual point. It is assumed the point is in the frame corresponding to the TransformCallback.
Definition at line 167 of file shape_mask.cpp.
void point_containment_filter::ShapeMask::maskContainment | ( | const sensor_msgs::PointCloud2 & | data_in, |
const Eigen::Vector3d & | sensor_pos, | ||
const double | min_sensor_dist, | ||
const double | max_sensor_dist, | ||
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 113 of file shape_mask.cpp.
void point_containment_filter::ShapeMask::removeShape | ( | ShapeHandle | handle | ) |
Definition at line 98 of file shape_mask.cpp.
void point_containment_filter::ShapeMask::setTransformCallback | ( | const TransformCallback & | transform_callback | ) |
Definition at line 59 of file shape_mask.cpp.
Definition at line 127 of file shape_mask.h.
std::vector<bodies::BoundingSphere> point_containment_filter::ShapeMask::bspheres_ [private] |
Definition at line 129 of file shape_mask.h.
Definition at line 124 of file shape_mask.h.
Definition at line 123 of file shape_mask.h.
boost::mutex point_containment_filter::ShapeMask::shapes_lock_ [mutable, private] |
Definition at line 126 of file shape_mask.h.
Definition at line 122 of file shape_mask.h.
std::map<ShapeHandle, std::set<SeeShape, SortBodies>::iterator> point_containment_filter::ShapeMask::used_handles_ [private] |
Definition at line 128 of file shape_mask.h.