moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Classes | Public Types | Public Member Functions | Protected 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 std::function< bool(ShapeHandle, Eigen::Isometry3d &)> TransformCallback
 

Public Member Functions

 ShapeMask (const TransformCallback &transform_callback=TransformCallback())
 Construct the filter.
 
virtual ~ShapeMask ()
 Destructor to clean up.
 
ShapeHandle addShape (const shapes::ShapeConstPtr &shape, double scale=1.0, double padding=0.0)
 
void removeShape (ShapeHandle handle)
 
void setTransformCallback (const TransformCallback &transform_callback)
 
void maskContainment (const sensor_msgs::msg::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.
 
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.
 

Protected Attributes

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

Detailed Description

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

Definition at line 52 of file shape_mask.h.

Member Typedef Documentation

◆ TransformCallback

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

Definition at line 63 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 56 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 52 of file shape_mask.cpp.

◆ ~ShapeMask()

point_containment_filter::ShapeMask::~ShapeMask ( )
virtual

Destructor to clean up.

Definition at line 57 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 75 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 204 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 217 of file shape_mask.cpp.

◆ maskContainment()

void point_containment_filter::ShapeMask::maskContainment ( const sensor_msgs::msg::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 129 of file shape_mask.cpp.

◆ removeShape()

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

Definition at line 114 of file shape_mask.cpp.

◆ setTransformCallback()

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

Definition at line 69 of file shape_mask.cpp.

Member Data Documentation

◆ bodies_

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

Definition at line 120 of file shape_mask.h.

◆ bspheres_

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

Definition at line 121 of file shape_mask.h.

◆ shapes_lock_

std::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 119 of file shape_mask.h.

◆ transform_callback_

TransformCallback point_containment_filter::ShapeMask::transform_callback_
protected

Definition at line 116 of file shape_mask.h.


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