Classes | Typedefs | Enumerations | Functions | Variables
collision_detection_bullet Namespace Reference

Classes

struct  BroadphaseContactResultCallback
 Callback structure for both discrete and continuous broadphase collision pair. More...
 
struct  BroadphaseFilterCallback
 
class  BulletBVHManager
 A bounding volume hierarchy (BVH) implementation of a tesseract contact manager. More...
 
class  BulletCastBVHManager
 A bounding volume hierarchy (BVH) implementation of a tesseract contact manager. More...
 
class  BulletDiscreteBVHManager
 A bounding volume hierarchy (BVH) implementaiton of a discrete bullet manager. More...
 
struct  CastHullShape
 Casted collision shape used for checking if an object is collision free between two discrete poses. More...
 
class  CollisionObjectWrapper
 Tesseract bullet collision object. More...
 
struct  ContactTestData
 Bundles the data for a collision query. More...
 
struct  TesseractBroadphaseBridgedManifoldResult
 
class  TesseractCollisionPairCallback
 A callback function that is called as part of the broadphase collision checking. More...
 

Typedefs

template<typename Key , typename Value >
using AlignedMap = std::map< Key, Value, std::less< Key >, Eigen::aligned_allocator< std::pair< const Key, Value > >>
 
template<typename Key , typename Value >
using AlignedUnorderedMap = std::unordered_map< Key, Value, std::hash< Key >, std::equal_to< Key >, Eigen::aligned_allocator< std::pair< const Key, Value > >>
 
template<typename T >
using AlignedVector = std::vector< T, Eigen::aligned_allocator< T > >
 

Enumerations

enum  CollisionObjectType { CollisionObjectType::USE_SHAPE_TYPE = 0, CollisionObjectType::CONVEX_HULL = 1, CollisionObjectType::MULTI_SPHERE = 2, CollisionObjectType::SDF = 3 }
 

Functions

bool acmCheck (const std::string &body_1, const std::string &body_2, const collision_detection::AllowedCollisionMatrix *acm)
 Allowed = true. More...
 
btScalar addCastSingleResult (btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int, const btCollisionObjectWrapper *colObj1Wrap, int, ContactTestData &collisions)
 
void addCollisionObjectToBroadphase (const CollisionObjectWrapperPtr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
 Add the collision object to broadphase. More...
 
btScalar addDiscreteSingleResult (btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, const btCollisionObjectWrapper *colObj1Wrap, ContactTestData &collisions)
 Converts a bullet contact result to MoveIt format and adds it to the result data structure. More...
 
shapes::ShapePtr constructShape (const urdf::Geometry *geom)
 
Eigen::Vector3d convertBtToEigen (const btVector3 &v)
 Converts bullet vector to eigen vector. More...
 
btTransform convertEigenToBt (const Eigen::Isometry3d &t)
 Converts bullet transform to eigen transform. More...
 
btMatrix3x3 convertEigenToBt (const Eigen::Matrix3d &r)
 Converts eigen matrix to bullet matrix. More...
 
btQuaternion convertEigenToBt (const Eigen::Quaterniond &q)
 Converts eigen quaternion to bullet quaternion. More...
 
btVector3 convertEigenToBt (const Eigen::Vector3d &v)
 Converts eigen vector to bullet vector. More...
 
int createConvexHull (AlignedVector< Eigen::Vector3d > &vertices, std::vector< int > &faces, const AlignedVector< Eigen::Vector3d > &input, double shrink=-1, double shrinkClamp=-1)
 Create a convex hull from vertices using Bullet Convex Hull Computer. More...
 
btCollisionShape * createShapePrimitive (const shapes::Box *geom, const CollisionObjectType &collision_object_type)
 
btCollisionShape * createShapePrimitive (const shapes::Cone *geom, const CollisionObjectType &collision_object_type)
 
btCollisionShape * createShapePrimitive (const shapes::Cylinder *geom, const CollisionObjectType &collision_object_type)
 
btCollisionShape * createShapePrimitive (const shapes::Mesh *geom, const CollisionObjectType &collision_object_type, CollisionObjectWrapper *cow)
 
btCollisionShape * createShapePrimitive (const shapes::OcTree *geom, const CollisionObjectType &collision_object_type, CollisionObjectWrapper *cow)
 
btCollisionShape * createShapePrimitive (const shapes::ShapeConstPtr &geom, const CollisionObjectType &collision_object_type, CollisionObjectWrapper *cow)
 Casts a geometric shape into a btCollisionShape. More...
 
btCollisionShape * createShapePrimitive (const shapes::Sphere *geom, const CollisionObjectType &collision_object_type)
 
static void getActiveLinkNamesRecursive (std::vector< std::string > &active_links, const urdf::LinkConstSharedPtr &urdf_link, bool active)
 Recursively traverses robot from root to get all active links. More...
 
void getAverageSupport (const btConvexShape *shape, const btVector3 &localNormal, float &outsupport, btVector3 &outpt)
 Computes the local supporting vertex of a convex shape. More...
 
std::pair< std::string, std::string > getObjectPairKey (const std::string &obj1, const std::string &obj2)
 Get a key for two object to search the collision matrix. More...
 
bool isLinkActive (const std::vector< std::string > &active, const std::string &name)
 This will check if a link is active provided a list. If the list is empty the link is considered active. More...
 
bool isOnlyKinematic (const CollisionObjectWrapper *cow0, const CollisionObjectWrapper *cow1)
 Checks if the collision pair is kinematic vs kinematic objects. More...
 
CollisionObjectWrapperPtr makeCastCollisionObject (const CollisionObjectWrapperPtr &cow)
 
 MOVEIT_CLASS_FORWARD (BulletBVHManager)
 
 MOVEIT_CLASS_FORWARD (BulletCastBVHManager)
 
 MOVEIT_CLASS_FORWARD (BulletDiscreteBVHManager)
 
 MOVEIT_CLASS_FORWARD (CollisionObjectWrapper)
 
collision_detection::ContactprocessResult (ContactTestData &cdata, collision_detection::Contact &contact, const std::pair< std::string, std::string > &key, bool found)
 Stores a single contact result in the requested way. More...
 
void removeCollisionObjectFromBroadphase (const CollisionObjectWrapperPtr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
 Remove the collision object from broadphase. More...
 
void updateBroadphaseAABB (const CollisionObjectWrapperPtr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
 Update the Broadphase AABB for the input collision object. More...
 
void updateCollisionObjectFilters (const std::vector< std::string > &active, CollisionObjectWrapper &cow)
 Update a collision objects filters. More...
 
Eigen::Isometry3d urdfPose2Eigen (const urdf::Pose &pose)
 

Variables

const bool BULLET_COMPOUND_USE_DYNAMIC_AABB = true
 
const btScalar BULLET_DEFAULT_CONTACT_DISTANCE = 0.00f
 
const btScalar BULLET_EPSILON = 1e-3f
 
const btScalar BULLET_LENGTH_TOLERANCE = 0.001f METERS
 
const btScalar BULLET_MARGIN = 0.0f
 
const btScalar BULLET_SUPPORT_FUNC_TOLERANCE = 0.01f METERS
 

Typedef Documentation

◆ AlignedMap

template<typename Key , typename Value >
using collision_detection_bullet::AlignedMap = typedef std::map<Key, Value, std::less<Key>, Eigen::aligned_allocator<std::pair<const Key, Value> >>

Definition at line 56 of file basic_types.h.

◆ AlignedUnorderedMap

template<typename Key , typename Value >
using collision_detection_bullet::AlignedUnorderedMap = typedef std::unordered_map<Key, Value, std::hash<Key>, std::equal_to<Key>, Eigen::aligned_allocator<std::pair<const Key, Value> >>

Definition at line 60 of file basic_types.h.

◆ AlignedVector

template<typename T >
using collision_detection_bullet::AlignedVector = typedef std::vector<T, Eigen::aligned_allocator<T> >

Definition at line 53 of file basic_types.h.

Enumeration Type Documentation

◆ CollisionObjectType

Enumerator
USE_SHAPE_TYPE 

Infer the type from the type specified in the shapes::Shape class.

CONVEX_HULL 

Use the mesh in shapes::Shape but make it a convex hulls collision object (if not convex it will be converted)

MULTI_SPHERE 

Use the mesh and represent it by multiple spheres collision object.

SDF 

Use the mesh and rpresent it by a signed distance fields collision object.

Definition at line 62 of file basic_types.h.

Function Documentation

◆ acmCheck()

bool collision_detection_bullet::acmCheck ( const std::string &  body_1,
const std::string &  body_2,
const collision_detection::AllowedCollisionMatrix acm 
)
inline

Allowed = true.

Definition at line 91 of file bullet_utils.h.

◆ addCastSingleResult()

btScalar collision_detection_bullet::addCastSingleResult ( btManifoldPoint &  cp,
const btCollisionObjectWrapper *  colObj0Wrap,
int  ,
const btCollisionObjectWrapper *  colObj1Wrap,
int  ,
ContactTestData collisions 
)
inline

Definition at line 486 of file bullet_utils.h.

◆ addCollisionObjectToBroadphase()

void collision_detection_bullet::addCollisionObjectToBroadphase ( const CollisionObjectWrapperPtr &  cow,
const std::unique_ptr< btBroadphaseInterface > &  broadphase,
const std::unique_ptr< btCollisionDispatcher > &  dispatcher 
)
inline

Add the collision object to broadphase.

Parameters
cowThe collision objects
broadphaseThe bullet broadphase interface
dispatcherThe bullet collision dispatcher

Definition at line 949 of file bullet_utils.h.

◆ addDiscreteSingleResult()

btScalar collision_detection_bullet::addDiscreteSingleResult ( btManifoldPoint &  cp,
const btCollisionObjectWrapper *  colObj0Wrap,
const btCollisionObjectWrapper *  colObj1Wrap,
ContactTestData collisions 
)
inline

Converts a bullet contact result to MoveIt format and adds it to the result data structure.

Definition at line 453 of file bullet_utils.h.

◆ constructShape()

shapes::ShapePtr collision_detection_bullet::constructShape ( const urdf::Geometry *  geom)
inline

Definition at line 78 of file ros_bullet_utils.h.

◆ convertBtToEigen()

Eigen::Vector3d collision_detection_bullet::convertBtToEigen ( const btVector3 &  v)
inline

Converts bullet vector to eigen vector.

Definition at line 135 of file bullet_utils.h.

◆ convertEigenToBt() [1/4]

btTransform collision_detection_bullet::convertEigenToBt ( const Eigen::Isometry3d &  t)
inline

Converts bullet transform to eigen transform.

Definition at line 156 of file bullet_utils.h.

◆ convertEigenToBt() [2/4]

btMatrix3x3 collision_detection_bullet::convertEigenToBt ( const Eigen::Matrix3d r)
inline

Converts eigen matrix to bullet matrix.

Definition at line 148 of file bullet_utils.h.

◆ convertEigenToBt() [3/4]

btQuaternion collision_detection_bullet::convertEigenToBt ( const Eigen::Quaterniond q)
inline

Converts eigen quaternion to bullet quaternion.

Definition at line 141 of file bullet_utils.h.

◆ convertEigenToBt() [4/4]

btVector3 collision_detection_bullet::convertEigenToBt ( const Eigen::Vector3d v)
inline

Converts eigen vector to bullet vector.

Definition at line 129 of file bullet_utils.h.

◆ createConvexHull()

int collision_detection_bullet::createConvexHull ( AlignedVector< Eigen::Vector3d > &  vertices,
std::vector< int > &  faces,
const AlignedVector< Eigen::Vector3d > &  input,
double  shrink = -1,
double  shrinkClamp = -1 
)
inline

Create a convex hull from vertices using Bullet Convex Hull Computer.

Parameters
(Output)vertices A vector of vertices
(Output)faces The first values indicates the number of vertices that define the face followed by the vertice index
(input)input A vector of point to create a convex hull from
(input)shrink If positive, the convex hull is shrunken by that amount (each face is moved by "shrink" length units towards the center along its normal).
(input)shrinkClamp If positive, "shrink" is clamped to not exceed "shrinkClamp * innerRadius", where "innerRadius" is the minimum distance of a face to the center of the convex hull.
Returns
The number of faces. If less than zero an error occured when trying to create the convex hull

Definition at line 166 of file contact_checker_common.h.

◆ createShapePrimitive() [1/7]

btCollisionShape* collision_detection_bullet::createShapePrimitive ( const shapes::Box geom,
const CollisionObjectType collision_object_type 
)

Definition at line 77 of file bullet_utils.cpp.

◆ createShapePrimitive() [2/7]

btCollisionShape* collision_detection_bullet::createShapePrimitive ( const shapes::Cone geom,
const CollisionObjectType collision_object_type 
)

Definition at line 105 of file bullet_utils.cpp.

◆ createShapePrimitive() [3/7]

btCollisionShape* collision_detection_bullet::createShapePrimitive ( const shapes::Cylinder geom,
const CollisionObjectType collision_object_type 
)

Definition at line 96 of file bullet_utils.cpp.

◆ createShapePrimitive() [4/7]

btCollisionShape* collision_detection_bullet::createShapePrimitive ( const shapes::Mesh geom,
const CollisionObjectType collision_object_type,
CollisionObjectWrapper cow 
)

Definition at line 114 of file bullet_utils.cpp.

◆ createShapePrimitive() [5/7]

btCollisionShape* collision_detection_bullet::createShapePrimitive ( const shapes::OcTree geom,
const CollisionObjectType collision_object_type,
CollisionObjectWrapper cow 
)

Definition at line 191 of file bullet_utils.cpp.

◆ createShapePrimitive() [6/7]

btCollisionShape * collision_detection_bullet::createShapePrimitive ( const shapes::ShapeConstPtr geom,
const CollisionObjectType collision_object_type,
CollisionObjectWrapper cow 
)

Casts a geometric shape into a btCollisionShape.

Definition at line 261 of file bullet_utils.cpp.

◆ createShapePrimitive() [7/7]

btCollisionShape* collision_detection_bullet::createShapePrimitive ( const shapes::Sphere geom,
const CollisionObjectType collision_object_type 
)

Definition at line 89 of file bullet_utils.cpp.

◆ getActiveLinkNamesRecursive()

static void collision_detection_bullet::getActiveLinkNamesRecursive ( std::vector< std::string > &  active_links,
const urdf::LinkConstSharedPtr &  urdf_link,
bool  active 
)
inlinestatic

Recursively traverses robot from root to get all active links.

Parameters
active_linksStores the active links
urdf_linkThe current urdf link representation
activeIndicates if link is considered active

Definition at line 54 of file ros_bullet_utils.h.

◆ getAverageSupport()

void collision_detection_bullet::getAverageSupport ( const btConvexShape *  shape,
const btVector3 &  localNormal,
float &  outsupport,
btVector3 &  outpt 
)
inline

Computes the local supporting vertex of a convex shape.

If multiple vertices with equal support products exists, their average is calculated and returned.

Parameters
shapeThe convex shape to check
localNormalThe support direction to search for in shape local coordinates
outsupportThe value of the calculated support mapping
outptThe computed support point

Definition at line 409 of file bullet_utils.h.

◆ getObjectPairKey()

std::pair<std::string, std::string> collision_detection_bullet::getObjectPairKey ( const std::string &  obj1,
const std::string &  obj2 
)
inline

Get a key for two object to search the collision matrix.

Parameters
obj1First collision object name
obj2Second collision object name
Returns
The collision pair key

Definition at line 56 of file contact_checker_common.h.

◆ isLinkActive()

bool collision_detection_bullet::isLinkActive ( const std::vector< std::string > &  active,
const std::string &  name 
)
inline

This will check if a link is active provided a list. If the list is empty the link is considered active.

Parameters
activeList of active link names
nameThe name of link to check if it is active.

Definition at line 66 of file contact_checker_common.h.

◆ isOnlyKinematic()

bool collision_detection_bullet::isOnlyKinematic ( const CollisionObjectWrapper cow0,
const CollisionObjectWrapper cow1 
)
inline

Checks if the collision pair is kinematic vs kinematic objects.

Definition at line 587 of file bullet_utils.h.

◆ makeCastCollisionObject()

CollisionObjectWrapperPtr collision_detection_bullet::makeCastCollisionObject ( const CollisionObjectWrapperPtr &  cow)
inline

Definition at line 818 of file bullet_utils.h.

◆ MOVEIT_CLASS_FORWARD() [1/4]

collision_detection_bullet::MOVEIT_CLASS_FORWARD ( BulletBVHManager  )

◆ MOVEIT_CLASS_FORWARD() [2/4]

collision_detection_bullet::MOVEIT_CLASS_FORWARD ( BulletCastBVHManager  )

◆ MOVEIT_CLASS_FORWARD() [3/4]

collision_detection_bullet::MOVEIT_CLASS_FORWARD ( BulletDiscreteBVHManager  )

◆ MOVEIT_CLASS_FORWARD() [4/4]

collision_detection_bullet::MOVEIT_CLASS_FORWARD ( CollisionObjectWrapper  )

◆ processResult()

collision_detection::Contact* collision_detection_bullet::processResult ( ContactTestData cdata,
collision_detection::Contact contact,
const std::pair< std::string, std::string > &  key,
bool  found 
)
inline

Stores a single contact result in the requested way.

Parameters
foundIndicates if a contact for this pair of objects has already been found
Returns
Pointer to the newly inserted contact

Definition at line 74 of file contact_checker_common.h.

◆ removeCollisionObjectFromBroadphase()

void collision_detection_bullet::removeCollisionObjectFromBroadphase ( const CollisionObjectWrapperPtr &  cow,
const std::unique_ptr< btBroadphaseInterface > &  broadphase,
const std::unique_ptr< btCollisionDispatcher > &  dispatcher 
)
inline

Remove the collision object from broadphase.

Parameters
cowThe collision objects
broadphaseThe bullet broadphase interface
dispatcherThe bullet collision dispatcher

Definition at line 931 of file bullet_utils.h.

◆ updateBroadphaseAABB()

void collision_detection_bullet::updateBroadphaseAABB ( const CollisionObjectWrapperPtr &  cow,
const std::unique_ptr< btBroadphaseInterface > &  broadphase,
const std::unique_ptr< btCollisionDispatcher > &  dispatcher 
)
inline

Update the Broadphase AABB for the input collision object.

Parameters
cowThe collision objects
broadphaseThe bullet broadphase interface
dispatcherThe bullet collision dispatcher

Definition at line 916 of file bullet_utils.h.

◆ updateCollisionObjectFilters()

void collision_detection_bullet::updateCollisionObjectFilters ( const std::vector< std::string > &  active,
CollisionObjectWrapper cow 
)
inline

Update a collision objects filters.

Parameters
activeA list of active collision objects
cowThe collision object to update.
continuousIndicate if the object is a continuous collision object.

Currently continuous collision objects can only be checked against static objects. Continuous to Continuous collision checking is currently not supports. TODO LEVI: Add support for Continuous to Continuous collision checking.

Definition at line 794 of file bullet_utils.h.

◆ urdfPose2Eigen()

Eigen::Isometry3d collision_detection_bullet::urdfPose2Eigen ( const urdf::Pose &  pose)
inline

Definition at line 115 of file ros_bullet_utils.h.

Variable Documentation

◆ BULLET_COMPOUND_USE_DYNAMIC_AABB

const bool collision_detection_bullet::BULLET_COMPOUND_USE_DYNAMIC_AABB = true

Definition at line 86 of file bullet_utils.h.

◆ BULLET_DEFAULT_CONTACT_DISTANCE

const btScalar collision_detection_bullet::BULLET_DEFAULT_CONTACT_DISTANCE = 0.00f

Definition at line 85 of file bullet_utils.h.

◆ BULLET_EPSILON

const btScalar collision_detection_bullet::BULLET_EPSILON = 1e-3f

Definition at line 84 of file bullet_utils.h.

◆ BULLET_LENGTH_TOLERANCE

const btScalar collision_detection_bullet::BULLET_LENGTH_TOLERANCE = 0.001f METERS

Definition at line 83 of file bullet_utils.h.

◆ BULLET_MARGIN

const btScalar collision_detection_bullet::BULLET_MARGIN = 0.0f

Definition at line 81 of file bullet_utils.h.

◆ BULLET_SUPPORT_FUNC_TOLERANCE

const btScalar collision_detection_bullet::BULLET_SUPPORT_FUNC_TOLERANCE = 0.01f METERS

Definition at line 82 of file bullet_utils.h.



moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sat Apr 27 2024 02:25:26