Classes | Namespaces | Macros | Functions | Variables
bullet_utils.h File Reference
#include <btBulletCollisionCommon.h>
#include <geometric_shapes/mesh_operations.h>
#include <ros/console.h>
#include <moveit/collision_detection_bullet/bullet_integration/basic_types.h>
#include <moveit/collision_detection_bullet/bullet_integration/contact_checker_common.h>
#include <moveit/collision_detection/collision_common.h>
#include <moveit/macros/declare_ptr.h>
#include <moveit/macros/class_forward.h>
Include dependency graph for bullet_utils.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  collision_detection_bullet::BroadphaseContactResultCallback
 Callback structure for both discrete and continuous broadphase collision pair. More...
 
struct  collision_detection_bullet::BroadphaseFilterCallback
 
struct  collision_detection_bullet::CastHullShape
 Casted collision shape used for checking if an object is collision free between two discrete poses. More...
 
class  collision_detection_bullet::CollisionObjectWrapper
 Tesseract bullet collision object. More...
 
struct  collision_detection_bullet::TesseractBroadphaseBridgedManifoldResult
 
class  collision_detection_bullet::TesseractCollisionPairCallback
 A callback function that is called as part of the broadphase collision checking. More...
 

Namespaces

 collision_detection_bullet
 

Macros

#define METERS
 

Functions

bool collision_detection_bullet::acmCheck (const std::string &body_1, const std::string &body_2, const collision_detection::AllowedCollisionMatrix *acm)
 Allowed = true. More...
 
btScalar collision_detection_bullet::addCastSingleResult (btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int, const btCollisionObjectWrapper *colObj1Wrap, int, ContactTestData &collisions)
 
void collision_detection_bullet::addCollisionObjectToBroadphase (const CollisionObjectWrapperPtr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
 Add the collision object to broadphase. More...
 
btScalar collision_detection_bullet::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...
 
Eigen::Vector3d collision_detection_bullet::convertBtToEigen (const btVector3 &v)
 Converts bullet vector to eigen vector. More...
 
btTransform collision_detection_bullet::convertEigenToBt (const Eigen::Isometry3d &t)
 Converts bullet transform to eigen transform. More...
 
btMatrix3x3 collision_detection_bullet::convertEigenToBt (const Eigen::Matrix3d &r)
 Converts eigen matrix to bullet matrix. More...
 
btQuaternion collision_detection_bullet::convertEigenToBt (const Eigen::Quaterniond &q)
 Converts eigen quaternion to bullet quaternion. More...
 
btVector3 collision_detection_bullet::convertEigenToBt (const Eigen::Vector3d &v)
 Converts eigen vector to bullet vector. More...
 
btCollisionShape * collision_detection_bullet::createShapePrimitive (const shapes::ShapeConstPtr &geom, const CollisionObjectType &collision_object_type, CollisionObjectWrapper *cow)
 Casts a geometric shape into a btCollisionShape. More...
 
void collision_detection_bullet::getAverageSupport (const btConvexShape *shape, const btVector3 &localNormal, float &outsupport, btVector3 &outpt)
 Computes the local supporting vertex of a convex shape. More...
 
bool collision_detection_bullet::isOnlyKinematic (const CollisionObjectWrapper *cow0, const CollisionObjectWrapper *cow1)
 Checks if the collision pair is kinematic vs kinematic objects. More...
 
CollisionObjectWrapperPtr collision_detection_bullet::makeCastCollisionObject (const CollisionObjectWrapperPtr &cow)
 
 collision_detection_bullet::MOVEIT_CLASS_FORWARD (CollisionObjectWrapper)
 
void collision_detection_bullet::removeCollisionObjectFromBroadphase (const CollisionObjectWrapperPtr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
 Remove the collision object from broadphase. More...
 
void collision_detection_bullet::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 collision_detection_bullet::updateCollisionObjectFilters (const std::vector< std::string > &active, CollisionObjectWrapper &cow)
 Update a collision objects filters. More...
 

Variables

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

Macro Definition Documentation

◆ METERS

#define METERS

Definition at line 79 of file bullet_utils.h.



moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Fri May 3 2024 02:28:41