Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
point_containment_filter::ShapeMask Class Reference

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. More...
 
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. More...
 
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. More...
 
void removeShape (ShapeHandle handle)
 
void setTransformCallback (const TransformCallback &transform_callback)
 
 ShapeMask (const TransformCallback &transform_callback=TransformCallback())
 Construct the filter. More...
 
 ~ShapeMask ()
 Destructor to clean up. More...
 

Private Member Functions

void freeMemory ()
 Free memory. More...
 

Private Attributes

std::set< SeeShape, SortBodiesbodies_
 
std::vector< bodies::BoundingSpherebspheres_
 
ShapeHandle min_handle_
 
ShapeHandle next_handle_
 
boost::mutex shapes_lock_
 
TransformCallback transform_callback_
 
std::map< ShapeHandle, std::set< SeeShape, SortBodies >::iterator > used_handles_
 

Detailed Description

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

Definition at line 55 of file shape_mask.h.

Member Typedef Documentation

typedef boost::function<bool(ShapeHandle, Eigen::Affine3d&)> point_containment_filter::ShapeMask::TransformCallback

Definition at line 66 of file shape_mask.h.

Member Enumeration Documentation

anonymous enum

The possible values of a mask computed for a point.

Enumerator
INSIDE 
OUTSIDE 
CLIP 

Definition at line 59 of file shape_mask.h.

Constructor & Destructor Documentation

point_containment_filter::ShapeMask::ShapeMask ( const TransformCallback transform_callback = TransformCallback())

Construct the filter.

Definition at line 42 of file shape_mask.cpp.

point_containment_filter::ShapeMask::~ShapeMask ( )

Destructor to clean up.

Definition at line 47 of file shape_mask.cpp.

Member Function Documentation

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 187 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 176 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.

Member Data Documentation

std::set<SeeShape, SortBodies> point_containment_filter::ShapeMask::bodies_
private

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.

ShapeHandle point_containment_filter::ShapeMask::min_handle_
private

Definition at line 124 of file shape_mask.h.

ShapeHandle point_containment_filter::ShapeMask::next_handle_
private

Definition at line 123 of file shape_mask.h.

boost::mutex point_containment_filter::ShapeMask::shapes_lock_
mutableprivate

Definition at line 126 of file shape_mask.h.

TransformCallback point_containment_filter::ShapeMask::transform_callback_
private

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.


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


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Sun Oct 18 2020 13:17:23