Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
robot_body_filter::RayCastingShapeMask Class Reference

This class manages a set of bodies in space and is able to test point(cloud)s against this set, whether the points are inside the set, shadowed by the set when viewed from a given sensor, or clipped by the given sensor clipping distance. More...

#include <RayCastingShapeMask.h>

Inheritance diagram for robot_body_filter::RayCastingShapeMask:
Inheritance graph
[legend]

Classes

struct  RayCastingShapeMaskPIMPL
 

Public Types

enum  MaskValue : std::uint8_t { MaskValue::INSIDE = 0, MaskValue::OUTSIDE = 1, MaskValue::CLIP = 2, MaskValue::SHADOW = 3 }
 

Public Member Functions

MultiShapeHandle addShape (const shapes::ShapeConstPtr &shape, double containsScale, double containsPadding, double shadowScale, double shadowPadding, double bsphereScale, double bspherePadding, double bboxScale, double bboxPadding, bool updateInternalStructures=true, const std::string &name="")
 Add the given shape to the set of filtered bodies. The internally created body will be transformed by the TransformCallback to which the handle of this shape will be passed. More...
 
MultiShapeHandle addShape (const shapes::ShapeConstPtr &shape, double scale=1.0, double padding=0.0, bool updateInternalStructures=true, const std::string &name="")
 Add the given shape to the set of filtered bodies. The internally created body will be transformed by the TransformCallback to which the handle of this shape will be passed. More...
 
std::map< point_containment_filter::ShapeHandle, const bodies::Body * > getBodies () const
 Provides the map of shape handle to corresponding body (for all added shapes). More...
 
std::map< point_containment_filter::ShapeHandle, const bodies::Body * > getBodiesForBoundingBox () const
 Provides the map of shape handle to corresponding body for shapes that should be used in bounding box computation. More...
 
std::map< point_containment_filter::ShapeHandle, const bodies::Body * > getBodiesForBoundingSphere () const
 Provides the map of shape handle to corresponding body for shapes that should be used in bounding sphere computation. More...
 
std::map< point_containment_filter::ShapeHandle, const bodies::Body * > getBodiesForContainsTest () const
 Provides the map of shape handle to corresponding body for shapes that should be used in contains tests. More...
 
std::map< point_containment_filter::ShapeHandle, const bodies::Body * > getBodiesForShadowTest () const
 Provides the map of shape handle to corresponding body for shapes that should be used in shadow testing. More...
 
bodies::BoundingSphere getBoundingSphere () const
 Get the bounding sphere containing all registered shapes. More...
 
std::map< point_containment_filter::ShapeHandle, bodies::BoundingSpheregetBoundingSpheres () const
 Get the map of bounding spheres of all registered shapes. More...
 
std::map< point_containment_filter::ShapeHandle, bodies::BoundingSpheregetBoundingSpheresForContainsTest () const
 Get the map of bounding spheres of all registered shapes that are used for testing INSIDE points. More...
 
void maskContainmentAndShadows (const Cloud &data, std::vector< MaskValue > &mask, const Eigen::Vector3d &sensorPos=Eigen::Vector3d::Zero())
 Decide whether the points in data are either INSIDE the robot, OUTSIDE of it, SHADOWed by the robot body, or CLIPped by min/max sensor measurement distance. INSIDE points can also be viewed as being SHADOW points, but in this algorithm, INSIDE has precedence. Invalid points (containing NaNs) are reported as OUTSIDE. More...
 
void maskContainmentAndShadows (const Eigen::Vector3f &data, MaskValue &mask, const Eigen::Vector3d &sensorPos=Eigen::Vector3d::Zero(), bool updateBodyPoses=true)
 Decide whether the point is either INSIDE the robot, OUTSIDE of it, SHADOWed by the robot body, or CLIPped by min/max sensor measurement distance. INSIDE points can also be viewed as being SHADOW points, but in this algorithm, INSIDE has precedence. Invalid points (containing NaNs) are reported as OUTSIDE. More...
 
 RayCastingShapeMask (const TransformCallback &transformCallback, double minSensorDist=0.0, double maxSensorDist=1e10, bool doClipping=true, bool doContainsTest=true, bool doShadowTest=true, double maxShadowDist=-1.0)
 
void removeShape (const MultiShapeHandle &handle, bool updateInternalStructures=true)
 Remove the shape identified by the given handle from the filtering mask. More...
 
void setIgnoreInContainsTest (std::unordered_set< MultiShapeHandle > ignoreInContainsTest, bool updateInternalStructures=true)
 Set the shapes to be ignored when doing test for INSIDE in maskContainmentAndShadows. More...
 
void setIgnoreInShadowTest (std::unordered_set< MultiShapeHandle > ignoreInShadowTest, bool updateInternalStructures=true)
 Set the shapes to be ignored when doing test for SHADOW in maskContainmentAndShadows. More...
 
void setTransformCallback (const TransformCallback &transform_callback)
 Set the callback which is called whenever a pose of a body needs to be updated. More...
 
void updateBodyPoses ()
 Update the poses of bodies and recompute corresponding bounding spheres. More...
 
void updateInternalShapeLists ()
 Update internal structures. Should be called whenever a shape is added, removed or ignored. By default, it is called automatically by the methods that affect the list of shapes. However, for efficiency, the caller can tell these methods to not update the shape lists and call this when a batch operation is finished. More...
 
virtual ~RayCastingShapeMask ()
 

Protected Member Functions

void classifyPointNoLock (const Eigen::Vector3d &data, MaskValue &mask, const Eigen::Vector3d &sensorPos)
 Decide whether the point is either INSIDE the robot, OUTSIDE of it, SHADOWed by the robot body, or CLIPped by min/max sensor measurement distance. INSIDE points can also be viewed as being SHADOW points, but in this algorithm, INSIDE has precedence. Invalid points (containing NaNs) are reported as OUTSIDE. More...
 
bodies::BoundingSphere getBoundingSphereForContainsTestNoLock () const
 Get the bounding sphere containing all shapes that are to be used in the contains test. More...
 
bodies::BoundingSphere getBoundingSphereNoLock () const
 Get the bounding sphere containing all registered shapes. More...
 
void updateBodyPosesNoLock ()
 Update the poses of bodies_ and recompute corresponding bspheres_ and boundingBoxes. More...
 
- Protected Member Functions inherited from point_containment_filter::ShapeMask
ShapeHandle addShape (const shapes::ShapeConstPtr &shape, double scale=1.0, double padding=0.0)
 
int getMaskContainment (const Eigen::Vector3d &pt) const
 
int getMaskContainment (double x, double y, double z) const
 
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)
 
void removeShape (ShapeHandle handle)
 
void setTransformCallback (const TransformCallback &transform_callback)
 
 ShapeMask (const TransformCallback &transform_callback=TransformCallback())
 
virtual ~ShapeMask ()
 

Protected Attributes

std::vector< size_t > bspheresBodyIndices
 Contains indices of bodies (as listed in this->bodies_) which correspond to bounding spheres in this->bspheres_. Indices in this vector correspond to indices in bspheres_. Values of this vector correspond to indices in bodies_. More...
 
std::vector< bodies::BoundingSpherebspheresForContainsTest
 Bounding spheres to be used for classifying INSIDE points. More...
 
std::vector< size_t > bspheresForContainsTestBodyIndices
 Contains indices of bodies (as listed in this->bodies_) which correspond to bounding spheres in this->bspheresForContainsTest. Indices in this vector correspond to indices in bspheresForContainsTest. Values of this vector correspond to indices in bodies_. More...
 
std::unique_ptr< RayCastingShapeMaskPIMPLdata
 Implementation-private data. More...
 
bool doClipping = true
 Classify for CLIP during masking. More...
 
bool doContainsTest = true
 Classify for INSIDE during masking. More...
 
bool doShadowTest = true
 Classify for SHADOW during masking. More...
 
std::unordered_set< MultiShapeHandleignoreInBbox
 Shapes to be ignored when computing the robot's bounding box. More...
 
std::unordered_set< MultiShapeHandleignoreInBsphere
 Shapes to be ignored when computing the robot's bounding sphere. More...
 
std::unordered_set< MultiShapeHandleignoreInContainsTest
 Shapes to be ignored when doing test for INSIDE in maskContainmentAndShadows. More...
 
std::unordered_set< MultiShapeHandleignoreInShadowTest
 Shapes to be ignored when doing test for SHADOW in maskContainmentAndShadows. E.g. the sensor collision shape should be listed here. More...
 
double maxSensorDist
 Maximum sensing distance of the sensor. More...
 
double maxShadowDist
 Maximum distance of a point classified as SHADOW (further are OUTSIDE). More...
 
double minSensorDist
 Minimum sensing distance of the sensor. More...
 
- Protected Attributes inherited from point_containment_filter::ShapeMask
std::set< SeeShape, SortBodiesbodies_
 
std::vector< bodies::BoundingSpherebspheres_
 
boost::mutex shapes_lock_
 
TransformCallback transform_callback_
 
 CLIP
 
 INSIDE
 
 OUTSIDE
 

Additional Inherited Members

- Protected Types inherited from point_containment_filter::ShapeMask
typedef boost::function< bool(ShapeHandle, Eigen::Isometry3d &)> TransformCallback
 

Detailed Description

This class manages a set of bodies in space and is able to test point(cloud)s against this set, whether the points are inside the set, shadowed by the set when viewed from a given sensor, or clipped by the given sensor clipping distance.

The mask works in the so-called filtering frame, which is any arbitrary TF frame. The TransformCallback you need to provide should transform all bodies to the filtering frame. All points passed to the masking functions are also expected to be in the filtering frame.

Important tip: do not forget to include the sensor's body in setIgnoreInShadowTest() call, otherwise all points will be shadowed by the sensor's body.

Due to limitations of the C++ API, there are some methods of the parent ShapeMask class that are forbidden to be used:

Also, constants ShapeMask::INSIDE, ShapeMask::OUTSIDE, ShapeMask::CLIP should be avoided and their RayCastingShapeMask:: counterparts should be used. In any case, the ShapeMask:: constants are binary-compatible with the corresponding RayCastingShapeMask:: constants, so if you don't need shadow filtering, you can keep using the ShapeMask:: constants (although it is strongly discouraged).

Definition at line 79 of file RayCastingShapeMask.h.

Member Enumeration Documentation

◆ MaskValue

Enumerator
INSIDE 

The point is inside robot body.

OUTSIDE 

The point is outside robot body and is not a shadow (invalid points with NaNs also fall here).

CLIP 

The point is outside measurement range.

SHADOW 

Line segment sensor-point intersects the robot body and the point is not INSIDE.

Definition at line 83 of file RayCastingShapeMask.h.

Constructor & Destructor Documentation

◆ RayCastingShapeMask()

robot_body_filter::RayCastingShapeMask::RayCastingShapeMask ( const TransformCallback transformCallback,
double  minSensorDist = 0.0,
double  maxSensorDist = 1e10,
bool  doClipping = true,
bool  doContainsTest = true,
bool  doShadowTest = true,
double  maxShadowDist = -1.0 
)
explicit
Parameters
transformCallback
minSensorDist
maxSensorDist
doClipping
doContainsTest
doShadowTest

Definition at line 38 of file RayCastingShapeMask.cpp.

◆ ~RayCastingShapeMask()

robot_body_filter::RayCastingShapeMask::~RayCastingShapeMask ( )
virtualdefault

Member Function Documentation

◆ addShape() [1/2]

MultiShapeHandle robot_body_filter::RayCastingShapeMask::addShape ( const shapes::ShapeConstPtr shape,
double  containsScale,
double  containsPadding,
double  shadowScale,
double  shadowPadding,
double  bsphereScale,
double  bspherePadding,
double  bboxScale,
double  bboxPadding,
bool  updateInternalStructures = true,
const std::string &  name = "" 
)

Add the given shape to the set of filtered bodies. The internally created body will be transformed by the TransformCallback to which the handle of this shape will be passed.

Parameters
shapeThe shape to be filtered.
containsScaleScale of the shape to be used in contains tests.
containsPaddingPadding of the shape to be used in contains tests.
shadowScaleScale of the shape to be used in shadow tests.
shadowPaddingPadding of the shape to be used in shadow tests.
bsphereScaleScale of the shape to be used in bounding sphere computation.
bspherePaddingPadding of the shape to be used in bounding sphere computation.
bboxScaleScale of the shape to be used in bounding box computation.
bboxPaddingPadding of the shape to be used in bounding box computation.
updateInternalStructuresSet to true if only adding a single shape. If adding a batch of shapes, set this to false and call updateInternalStructures() manually at the end of the batch.
nameOptional name of the shape. Used when reporting problems with the shape transforms.
Returns
A handle of the shape. It can be used for removing the shape. The contains and shadow member handles will be passed as the first argument of TransformCallback when asking for the transform of this shape's body.
See also
updateInternalShapeLists()

Definition at line 349 of file RayCastingShapeMask.cpp.

◆ addShape() [2/2]

MultiShapeHandle robot_body_filter::RayCastingShapeMask::addShape ( const shapes::ShapeConstPtr shape,
double  scale = 1.0,
double  padding = 0.0,
bool  updateInternalStructures = true,
const std::string &  name = "" 
)

Add the given shape to the set of filtered bodies. The internally created body will be transformed by the TransformCallback to which the handle of this shape will be passed.

Parameters
shapeThe shape to be filtered.
scaleScale of the shape to be used in both contains and shadow tests.
paddingPadding of the shape to be used in both contains and shadow tests.
updateInternalStructuresSet to true if only adding a single shape. If adding a batch of shapes, set this to false and call updateInternalStructures() manually at the end of the batch.
nameOptional name of the shape. Used when reporting problems with the shape transforms.
Returns
A handle of the shape. It can be used for removing the shape. The contains and shadow member handles will be passed as the first argument of TransformCallback when asking for the transform of this shape's body.
See also
updateInternalShapeLists()

Definition at line 341 of file RayCastingShapeMask.cpp.

◆ classifyPointNoLock()

void robot_body_filter::RayCastingShapeMask::classifyPointNoLock ( const Eigen::Vector3d data,
RayCastingShapeMask::MaskValue mask,
const Eigen::Vector3d sensorPos 
)
protected

Decide whether the point is either INSIDE the robot, OUTSIDE of it, SHADOWed by the robot body, or CLIPped by min/max sensor measurement distance. INSIDE points can also be viewed as being SHADOW points, but in this algorithm, INSIDE has precedence. Invalid points (containing NaNs) are reported as OUTSIDE.

Parameters
[in]dataThe input point. It has to be in the same frame into which transform_callback_ transforms the body parts.
[out]maskThe mask value of the given point.
[in]sensorPosPosition of the sensor in the pointcloud frame.
Note
Contrasting to maskContainmentAndShadows(), this method doesn't update link poses and expects them to be correctly updated by a prior call to updateBodyPoses(). It also doesn't lock shapes_mutex_.

Definition at line 269 of file RayCastingShapeMask.cpp.

◆ getBodies()

std::map< point_containment_filter::ShapeHandle, const bodies::Body * > robot_body_filter::RayCastingShapeMask::getBodies ( ) const

Provides the map of shape handle to corresponding body (for all added shapes).

Returns
Map shape_handle->body* .
Note
Shapes with scale or padding for contains test different from the scale or padding for shadow test, will be represented by two bodies here.

Definition at line 469 of file RayCastingShapeMask.cpp.

◆ getBodiesForBoundingBox()

std::map< point_containment_filter::ShapeHandle, const bodies::Body * > robot_body_filter::RayCastingShapeMask::getBodiesForBoundingBox ( ) const

Provides the map of shape handle to corresponding body for shapes that should be used in bounding box computation.

Returns
Map shape_handle->body* .
Note
The returned bodies should not be changed.

Definition at line 517 of file RayCastingShapeMask.cpp.

◆ getBodiesForBoundingSphere()

std::map< point_containment_filter::ShapeHandle, const bodies::Body * > robot_body_filter::RayCastingShapeMask::getBodiesForBoundingSphere ( ) const

Provides the map of shape handle to corresponding body for shapes that should be used in bounding sphere computation.

Returns
Map shape_handle->body* .
Note
The returned bodies should not be changed.

Definition at line 505 of file RayCastingShapeMask.cpp.

◆ getBodiesForContainsTest()

std::map< point_containment_filter::ShapeHandle, const bodies::Body * > robot_body_filter::RayCastingShapeMask::getBodiesForContainsTest ( ) const

Provides the map of shape handle to corresponding body for shapes that should be used in contains tests.

Returns
Map shape_handle->body* .

Definition at line 481 of file RayCastingShapeMask.cpp.

◆ getBodiesForShadowTest()

std::map< point_containment_filter::ShapeHandle, const bodies::Body * > robot_body_filter::RayCastingShapeMask::getBodiesForShadowTest ( ) const

Provides the map of shape handle to corresponding body for shapes that should be used in shadow testing.

Returns
Map shape_handle->body* .
Note
The returned bodies should not be changed.

Definition at line 493 of file RayCastingShapeMask.cpp.

◆ getBoundingSphere()

bodies::BoundingSphere robot_body_filter::RayCastingShapeMask::getBoundingSphere ( ) const

Get the bounding sphere containing all registered shapes.

Returns
The bounding sphere of the mask.
Note
If scale or padding for contains test differ from scale or padding for the shadow test, the maximum of the two bounding spheres is returned.
Is only updated during updateBodyPoses().

Definition at line 98 of file RayCastingShapeMask.cpp.

◆ getBoundingSphereForContainsTestNoLock()

bodies::BoundingSphere robot_body_filter::RayCastingShapeMask::getBoundingSphereForContainsTestNoLock ( ) const
protected

Get the bounding sphere containing all shapes that are to be used in the contains test.

Returns
The bounding sphere of the mask.

Definition at line 109 of file RayCastingShapeMask.cpp.

◆ getBoundingSphereNoLock()

bodies::BoundingSphere robot_body_filter::RayCastingShapeMask::getBoundingSphereNoLock ( ) const
protected

Get the bounding sphere containing all registered shapes.

Returns
The bounding sphere of the mask.

Definition at line 104 of file RayCastingShapeMask.cpp.

◆ getBoundingSpheres()

std::map< point_containment_filter::ShapeHandle, bodies::BoundingSphere > robot_body_filter::RayCastingShapeMask::getBoundingSpheres ( ) const

Get the map of bounding spheres of all registered shapes.

Returns
The map of bounding spheres.
Note
If scale or padding for contains test differ from scale or padding for the shadow test for a shape, it will be represented by two bodies.
Is only updated during updateBodyPoses().

Definition at line 57 of file RayCastingShapeMask.cpp.

◆ getBoundingSpheresForContainsTest()

std::map< point_containment_filter::ShapeHandle, bodies::BoundingSphere > robot_body_filter::RayCastingShapeMask::getBoundingSpheresForContainsTest ( ) const

Get the map of bounding spheres of all registered shapes that are used for testing INSIDE points.

Returns
The map of bounding spheres.
Note
Is only updated during updateBodyPoses().

Definition at line 78 of file RayCastingShapeMask.cpp.

◆ maskContainmentAndShadows() [1/2]

void robot_body_filter::RayCastingShapeMask::maskContainmentAndShadows ( const Cloud data,
std::vector< MaskValue > &  mask,
const Eigen::Vector3d sensorPos = Eigen::Vector3d::Zero() 
)

Decide whether the points in data are either INSIDE the robot, OUTSIDE of it, SHADOWed by the robot body, or CLIPped by min/max sensor measurement distance. INSIDE points can also be viewed as being SHADOW points, but in this algorithm, INSIDE has precedence. Invalid points (containing NaNs) are reported as OUTSIDE.

Parameters
[in]dataThe input pointcloud. It has to be in the same frame into which transform_callback_ transforms the body parts. The frame_id of the cloud is ignored.
[out]maskThe mask value of all the points. Ordered by point index.
[in]sensorPosPosition of the sensor in the pointcloud frame.
Note
Internally calls updateBodyPoses() to update link transforms.
Updates bspheres_/boundingBoxes to contain the bounding spheres/boxes of links.

◆ maskContainmentAndShadows() [2/2]

void robot_body_filter::RayCastingShapeMask::maskContainmentAndShadows ( const Eigen::Vector3f data,
RayCastingShapeMask::MaskValue mask,
const Eigen::Vector3d sensorPos = Eigen::Vector3d::Zero(),
bool  updateBodyPoses = true 
)

Decide whether the point is either INSIDE the robot, OUTSIDE of it, SHADOWed by the robot body, or CLIPped by min/max sensor measurement distance. INSIDE points can also be viewed as being SHADOW points, but in this algorithm, INSIDE has precedence. Invalid points (containing NaNs) are reported as OUTSIDE.

Parameters
[in]dataThe input point. It has to be in the same frame into which transform_callback_ transforms the body parts.
[out]maskThe mask value of the given point.
[in]sensorPosPosition of the sensor in the pointcloud frame.
Note
Internally calls updateBodyPoses() to update link transforms.
Updates bspheres_/boundingBoxes to contain the bounding spheres/boxes of links.

Definition at line 251 of file RayCastingShapeMask.cpp.

◆ removeShape()

void robot_body_filter::RayCastingShapeMask::removeShape ( const MultiShapeHandle handle,
bool  updateInternalStructures = true 
)

Remove the shape identified by the given handle from the filtering mask.

Parameters
handleThe handle returned by addShape().
updateInternalStructuresSet to true if only removing a single shape. If removing a batch of shapes, set this to false and call updateInternalStructures() manually at the end of the batch.
See also
updateInternalShapeLists()

Definition at line 399 of file RayCastingShapeMask.cpp.

◆ setIgnoreInContainsTest()

void robot_body_filter::RayCastingShapeMask::setIgnoreInContainsTest ( std::unordered_set< MultiShapeHandle ignoreInContainsTest,
bool  updateInternalStructures = true 
)

Set the shapes to be ignored when doing test for INSIDE in maskContainmentAndShadows.

Parameters
ignoreInContainsTestThe shapes to be ignored.
updateInternalStructuresIf false, the caller is responsible for calling updateInternalShapeLists().
See also
updateInternalShapeLists()

Definition at line 323 of file RayCastingShapeMask.cpp.

◆ setIgnoreInShadowTest()

void robot_body_filter::RayCastingShapeMask::setIgnoreInShadowTest ( std::unordered_set< MultiShapeHandle ignoreInShadowTest,
bool  updateInternalStructures = true 
)

Set the shapes to be ignored when doing test for SHADOW in maskContainmentAndShadows.

Parameters
ignoreInShadowTestThe shapes to be ignored.
updateInternalStructuresIf false, the caller is responsible for calling updateInternalShapeLists().
Note
E.g. the sensor collision shape should be listed here.
See also
updateInternalShapeLists()

Definition at line 332 of file RayCastingShapeMask.cpp.

◆ setTransformCallback()

void robot_body_filter::RayCastingShapeMask::setTransformCallback ( const TransformCallback transform_callback)

Set the callback which is called whenever a pose of a body needs to be updated.

Parameters
transform_callbackThe callback. First argument is the handle of the shape whose corresponding body is being updated. The second argument is the resulting transform. Return false if getting the transform failed, otherwise return true.

Definition at line 435 of file RayCastingShapeMask.cpp.

◆ updateBodyPoses()

void robot_body_filter::RayCastingShapeMask::updateBodyPoses ( )

Update the poses of bodies and recompute corresponding bounding spheres.

Note
Calls the TransformCallback given in constructor or set by setTransformCallback(). One call per registered shape will be made.

Definition at line 114 of file RayCastingShapeMask.cpp.

◆ updateBodyPosesNoLock()

void robot_body_filter::RayCastingShapeMask::updateBodyPosesNoLock ( )
protected

Update the poses of bodies_ and recompute corresponding bspheres_ and boundingBoxes.

Note
Calls transform_callback_
The caller has to hold a lock to shapes_mutex_.

Definition at line 120 of file RayCastingShapeMask.cpp.

◆ updateInternalShapeLists()

void robot_body_filter::RayCastingShapeMask::updateInternalShapeLists ( )

Update internal structures. Should be called whenever a shape is added, removed or ignored. By default, it is called automatically by the methods that affect the list of shapes. However, for efficiency, the caller can tell these methods to not update the shape lists and call this when a batch operation is finished.

See also
addShape()
removeShape()

Definition at line 441 of file RayCastingShapeMask.cpp.

Member Data Documentation

◆ bspheresBodyIndices

std::vector<size_t> robot_body_filter::RayCastingShapeMask::bspheresBodyIndices
protected

Contains indices of bodies (as listed in this->bodies_) which correspond to bounding spheres in this->bspheres_. Indices in this vector correspond to indices in bspheres_. Values of this vector correspond to indices in bodies_.

Definition at line 383 of file RayCastingShapeMask.h.

◆ bspheresForContainsTest

std::vector<bodies::BoundingSphere> robot_body_filter::RayCastingShapeMask::bspheresForContainsTest
protected

Bounding spheres to be used for classifying INSIDE points.

Definition at line 386 of file RayCastingShapeMask.h.

◆ bspheresForContainsTestBodyIndices

std::vector<size_t> robot_body_filter::RayCastingShapeMask::bspheresForContainsTestBodyIndices
protected

Contains indices of bodies (as listed in this->bodies_) which correspond to bounding spheres in this->bspheresForContainsTest. Indices in this vector correspond to indices in bspheresForContainsTest. Values of this vector correspond to indices in bodies_.

Definition at line 392 of file RayCastingShapeMask.h.

◆ data

std::unique_ptr<RayCastingShapeMaskPIMPL> robot_body_filter::RayCastingShapeMask::data
protected

Implementation-private data.

Definition at line 375 of file RayCastingShapeMask.h.

◆ doClipping

bool robot_body_filter::RayCastingShapeMask::doClipping = true
protected

Classify for CLIP during masking.

Definition at line 371 of file RayCastingShapeMask.h.

◆ doContainsTest

bool robot_body_filter::RayCastingShapeMask::doContainsTest = true
protected

Classify for INSIDE during masking.

Definition at line 372 of file RayCastingShapeMask.h.

◆ doShadowTest

bool robot_body_filter::RayCastingShapeMask::doShadowTest = true
protected

Classify for SHADOW during masking.

Definition at line 373 of file RayCastingShapeMask.h.

◆ ignoreInBbox

std::unordered_set<MultiShapeHandle> robot_body_filter::RayCastingShapeMask::ignoreInBbox
protected

Shapes to be ignored when computing the robot's bounding box.

Definition at line 402 of file RayCastingShapeMask.h.

◆ ignoreInBsphere

std::unordered_set<MultiShapeHandle> robot_body_filter::RayCastingShapeMask::ignoreInBsphere
protected

Shapes to be ignored when computing the robot's bounding sphere.

Definition at line 400 of file RayCastingShapeMask.h.

◆ ignoreInContainsTest

std::unordered_set<MultiShapeHandle> robot_body_filter::RayCastingShapeMask::ignoreInContainsTest
protected

Shapes to be ignored when doing test for INSIDE in maskContainmentAndShadows.

Definition at line 395 of file RayCastingShapeMask.h.

◆ ignoreInShadowTest

std::unordered_set<MultiShapeHandle> robot_body_filter::RayCastingShapeMask::ignoreInShadowTest
protected

Shapes to be ignored when doing test for SHADOW in maskContainmentAndShadows. E.g. the sensor collision shape should be listed here.

Definition at line 398 of file RayCastingShapeMask.h.

◆ maxSensorDist

double robot_body_filter::RayCastingShapeMask::maxSensorDist
protected

Maximum sensing distance of the sensor.

Definition at line 368 of file RayCastingShapeMask.h.

◆ maxShadowDist

double robot_body_filter::RayCastingShapeMask::maxShadowDist
protected

Maximum distance of a point classified as SHADOW (further are OUTSIDE).

Definition at line 369 of file RayCastingShapeMask.h.

◆ minSensorDist

double robot_body_filter::RayCastingShapeMask::minSensorDist
protected

Minimum sensing distance of the sensor.

Definition at line 367 of file RayCastingShapeMask.h.


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


robot_body_filter
Author(s): Eitan Marder-Eppstein, Tomas Petricek, Martin Pecka
autogenerated on Mon Feb 5 2024 03:33:49