Classes | Public Types | Public Member Functions | Protected Attributes | 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::Isometry3d &)> TransformCallback
 

Public Member Functions

ShapeHandle addShape (const shapes::ShapeConstPtr &shape, double scale=1.0, double padding=0.0)
 
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...
 
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...
 
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...
 
virtual ~ShapeMask ()
 Destructor to clean up. More...
 

Protected Attributes

std::set< SeeShape, SortBodiesbodies_
 
std::vector< bodies::BoundingSpherebspheres_
 
boost::mutex shapes_lock_
 Protects, bodies_ and bspheres_. All public methods acquire this mutex for their whole duration. More...
 
TransformCallback transform_callback_
 

Private Member Functions

void freeMemory ()
 Free memory. More...
 

Private Attributes

ShapeHandle min_handle_
 
ShapeHandle next_handle_
 
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 85 of file shape_mask.h.

Member Typedef Documentation

◆ TransformCallback

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

Definition at line 96 of file shape_mask.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum

The possible values of a mask computed for a point.

Enumerator
INSIDE 
OUTSIDE 
CLIP 

Definition at line 89 of file shape_mask.h.

Constructor & Destructor Documentation

◆ ShapeMask()

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

Construct the filter.

Definition at line 44 of file shape_mask.cpp.

◆ ~ShapeMask()

point_containment_filter::ShapeMask::~ShapeMask ( )
virtual

Destructor to clean up.

Definition at line 49 of file shape_mask.cpp.

Member Function Documentation

◆ addShape()

point_containment_filter::ShapeHandle point_containment_filter::ShapeMask::addShape ( const shapes::ShapeConstPtr shape,
double  scale = 1.0,
double  padding = 0.0 
)

Definition at line 67 of file shape_mask.cpp.

◆ freeMemory()

void point_containment_filter::ShapeMask::freeMemory ( )
private

Free memory.

Definition at line 54 of file shape_mask.cpp.

◆ getMaskContainment() [1/2]

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 179 of file shape_mask.cpp.

◆ getMaskContainment() [2/2]

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 190 of file shape_mask.cpp.

◆ maskContainment()

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 117 of file shape_mask.cpp.

◆ removeShape()

void point_containment_filter::ShapeMask::removeShape ( ShapeHandle  handle)

Definition at line 102 of file shape_mask.cpp.

◆ setTransformCallback()

void point_containment_filter::ShapeMask::setTransformCallback ( const TransformCallback transform_callback)

Definition at line 61 of file shape_mask.cpp.

Member Data Documentation

◆ bodies_

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

Definition at line 153 of file shape_mask.h.

◆ bspheres_

std::vector<bodies::BoundingSphere> point_containment_filter::ShapeMask::bspheres_
protected

Definition at line 154 of file shape_mask.h.

◆ min_handle_

ShapeHandle point_containment_filter::ShapeMask::min_handle_
private

Definition at line 161 of file shape_mask.h.

◆ next_handle_

ShapeHandle point_containment_filter::ShapeMask::next_handle_
private

Definition at line 160 of file shape_mask.h.

◆ shapes_lock_

boost::mutex point_containment_filter::ShapeMask::shapes_lock_
mutableprotected

Protects, bodies_ and bspheres_. All public methods acquire this mutex for their whole duration.

Definition at line 152 of file shape_mask.h.

◆ transform_callback_

TransformCallback point_containment_filter::ShapeMask::transform_callback_
protected

Definition at line 149 of file shape_mask.h.

◆ used_handles_

std::map<ShapeHandle, std::set<SeeShape, SortBodies>::iterator> point_containment_filter::ShapeMask::used_handles_
private

Definition at line 162 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 Mon May 27 2024 02:27:57