Public Member Functions | Protected Attributes | List of all members
tesseract_collision::tesseract_collision_fcl::FCLCollisionObjectWrapper Class Reference

This is a wrapper around FCL Collision Object Class which allows you to expand the AABB by the contact dist. More...

#include <fcl_collision_object_wrapper.h>

Inheritance diagram for tesseract_collision::tesseract_collision_fcl::FCLCollisionObjectWrapper:
Inheritance graph
[legend]

Public Member Functions

double getContactDistanceThreshold () const
 Get the collision objects contact distance threshold. More...
 
int getShapeIndex () const
 Get the shape index. This is the geometries index in the urdf. More...
 
void setContactDistanceThreshold (double contact_distance)
 Set the collision objects contact distance threshold. More...
 
void setShapeIndex (int index)
 Set the shape index. This is the geometries index in the urdf. More...
 
void updateAABB ()
 Update the internal AABB. This must be called instead of the base class computeAABB(). More...
 
- Public Member Functions inherited from fcl::CollisionObject< double >
const std::shared_ptr< const CollisionGeometry< S > > & collisionGeometry () const
 
 CollisionObject (const std::shared_ptr< CollisionGeometry< S >> &cgeom)
 
 CollisionObject (const std::shared_ptr< CollisionGeometry< S >> &cgeom, const Matrix3< S > &R, const Vector3< S > &T)
 
 CollisionObject (const std::shared_ptr< CollisionGeometry< S >> &cgeom, const Transform3< S > &tf)
 
void computeAABB ()
 
const AABB< S > & getAABB () const
 
const FCL_DEPRECATED CollisionGeometry< S > * getCollisionGeometry () const
 
getCostDensity () const
 
NODE_TYPE getNodeType () const
 
OBJECT_TYPE getObjectType () const
 
const Quaternion< S > getQuatRotation () const
 
const Matrix3< S > getRotation () const
 
const Transform3< S > & getTransform () const
 
const Vector3< S > getTranslation () const
 
void * getUserData () const
 
bool isFree () const
 
bool isIdentityTransform () const
 
bool isOccupied () const
 
bool isUncertain () const
 
void setCostDensity (S c)
 
void setIdentityTransform ()
 
void setQuatRotation (const Quaternion< S > &q)
 
void setRotation (const Matrix3< S > &R)
 
void setTransform (const Matrix3< S > &R, const Vector3< S > &T)
 
void setTransform (const Quaternion< S > &q, const Vector3< S > &T)
 
void setTransform (const Transform3< S > &tf)
 
void setTranslation (const Vector3< S > &T)
 
void setUserData (void *data)
 
 ~CollisionObject ()
 

Protected Attributes

double contact_distance_ { 0 }
 The contact distance threshold. More...
 
int shape_index_ { -1 }
 The shape index, which is the geometries index in the urdf. More...
 
- Protected Attributes inherited from fcl::CollisionObject< double >
AABB< S > aabb
 
std::shared_ptr< CollisionGeometry< S > > cgeom
 
std::shared_ptr< const CollisionGeometry< S > > cgeom_const
 
Transform3< S > t
 
void * user_data
 

Detailed Description

This is a wrapper around FCL Collision Object Class which allows you to expand the AABB by the contact dist.

This significantly improves performance when making distance requests if performing a contact tests type FIRST.

Definition at line 41 of file fcl_collision_object_wrapper.h.

Member Function Documentation

◆ getContactDistanceThreshold()

double tesseract_collision::tesseract_collision_fcl::FCLCollisionObjectWrapper::getContactDistanceThreshold ( ) const

Get the collision objects contact distance threshold.

Returns
The contact distance threshold.

Definition at line 37 of file fcl_collision_object_wrapper.cpp.

◆ getShapeIndex()

int tesseract_collision::tesseract_collision_fcl::FCLCollisionObjectWrapper::getShapeIndex ( ) const

Get the shape index. This is the geometries index in the urdf.

Returns
The shape index

Definition at line 59 of file fcl_collision_object_wrapper.cpp.

◆ setContactDistanceThreshold()

void tesseract_collision::tesseract_collision_fcl::FCLCollisionObjectWrapper::setContactDistanceThreshold ( double  contact_distance)

Set the collision objects contact distance threshold.

This automatically calls updateAABB() which increases the AABB by the contact distance.

Parameters
contact_distanceThe contact distance threshold.

Definition at line 31 of file fcl_collision_object_wrapper.cpp.

◆ setShapeIndex()

void tesseract_collision::tesseract_collision_fcl::FCLCollisionObjectWrapper::setShapeIndex ( int  index)

Set the shape index. This is the geometries index in the urdf.

Parameters
indexThe index

Definition at line 57 of file fcl_collision_object_wrapper.cpp.

◆ updateAABB()

void tesseract_collision::tesseract_collision_fcl::FCLCollisionObjectWrapper::updateAABB ( )

Update the internal AABB. This must be called instead of the base class computeAABB().

After setting the collision objects transform this must be called.

Definition at line 39 of file fcl_collision_object_wrapper.cpp.

Member Data Documentation

◆ contact_distance_

double tesseract_collision::tesseract_collision_fcl::FCLCollisionObjectWrapper::contact_distance_ { 0 }
protected

The contact distance threshold.

Definition at line 80 of file fcl_collision_object_wrapper.h.

◆ shape_index_

int tesseract_collision::tesseract_collision_fcl::FCLCollisionObjectWrapper::shape_index_ { -1 }
protected

The shape index, which is the geometries index in the urdf.

Definition at line 83 of file fcl_collision_object_wrapper.h.


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


tesseract_collision
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:53