Classes | Typedefs | Functions | Variables
tesseract_collision::tesseract_collision_bullet Namespace Reference

Classes

struct  BroadphaseContactResultCallback
 The BroadphaseContactResultCallback is used to report contact points. More...
 
struct  btPerturbedContactResult
 
struct  btSimplex
 
struct  btSupportVector
 
class  BulletCastBVHManager
 A BVH implementation of a tesseract contact manager. More...
 
class  BulletCastBVHManagerFactory
 
class  BulletCastSimpleManager
 A simple implementation of a tesseract manager which does not use BHV. More...
 
class  BulletCastSimpleManagerFactory
 
struct  BulletCollisionShape
 
class  BulletCollisionShapeCache
 
class  BulletDiscreteBVHManager
 A BVH implementation of a bullet manager. More...
 
class  BulletDiscreteBVHManagerFactory
 The yaml config for each of the factories below is the same. More...
 
class  BulletDiscreteSimpleManager
 A simple implementation of a bullet manager which does not use BHV. More...
 
class  BulletDiscreteSimpleManagerFactory
 
struct  CastBroadphaseContactResultCallback
 
struct  CastCollisionCollector
 
struct  CastHullShape
 This is a casted collision shape used for checking if an object is collision free between two transforms. More...
 
class  CollisionObjectWrapper
 This is a tesseract bullet collsion object. More...
 
struct  DiscreteBroadphaseContactResultCallback
 
struct  DiscreteCollisionCollector
 
struct  TesseractBridgedManifoldResult
 This is copied directly out of BulletWorld. More...
 
struct  TesseractBroadphaseBridgedManifoldResult
 
class  TesseractCollisionConfiguration
 This is a modified configuration that included the modified Bullet algorithms. More...
 
struct  TesseractCollisionConfigurationInfo
 
class  TesseractCollisionPairCallback
 A callback function that is called as part of the broadphase collision checking. More...
 
class  TesseractCompoundCollisionAlgorithm
 Supports collision between CompoundCollisionShapes and other collision shapes. More...
 
class  TesseractCompoundCompoundCollisionAlgorithm
 Supports collision between two btCompoundCollisionShape shapes. More...
 
struct  TesseractCompoundCompoundLeafCallback
 
struct  TesseractCompoundLeafCallback
 
class  TesseractConvexConvexAlgorithm
 This is a modifed Convex to Convex collision algorithm. More...
 
class  TesseractGjkPairDetector
 This is a modifed Convex to Convex collision algorithm. More...
 
class  TesseractOverlapFilterCallback
 This class is used to filter broadphase. More...
 

Typedefs

using COW = CollisionObjectWrapper
 
using Link2ConstCow = std::map< std::string, COW::ConstPtr >
 
using Link2Cow = std::map< std::string, COW::Ptr >
 

Functions

btScalar addCastSingleResult (btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int index0, const btCollisionObjectWrapper *colObj1Wrap, int index1, ContactTestData &collisions)
 
void addCollisionObjectToBroadphase (const COW::Ptr &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)
 
btScalar addDiscreteSingleResult (btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int index0, const btCollisionObjectWrapper *colObj1Wrap, int index1, ContactTestData &collisions)
 
static void btComputeSupport (const btConvexShape *convexA, const btTransform &localTransA, const btConvexShape *convexB, const btTransform &localTransB, const btVector3 &dir, bool check2d, btVector3 &supAworld, btVector3 &supBworld, btVector3 &aMinb)
 
static int btDoSimplex (btSimplex *simplex, btVector3 *dir)
 
static int btDoSimplex2 (btSimplex *simplex, btVector3 *dir)
 
static int btDoSimplex3 (btSimplex *simplex, btVector3 *dir)
 
static int btDoSimplex4 (btSimplex *simplex, btVector3 *dir)
 
void btSimplexAdd (btSimplex *s, const btSupportVector *v)
 
void btSimplexInit (btSimplex *s)
 
const btSupportVectorbtSimplexPoint (const btSimplex *s, int idx)
 
void btSimplexSet (btSimplex *s, size_t pos, const btSupportVector *a)
 
void btSimplexSetSize (btSimplex *s, int size)
 
int btSimplexSize (const btSimplex *s)
 
void btSupportCopy (btSupportVector *d, const btSupportVector *s)
 
void btTripleCross (const btVector3 *a, const btVector3 *b, const btVector3 *c, btVector3 *d)
 
void btVec3Copy (btVector3 *v, const btVector3 *w)
 
void btVec3Cross (btVector3 *d, const btVector3 *a, const btVector3 *b)
 
btScalar btVec3Dot (const btVector3 *a, const btVector3 *b)
 
int btVec3Eq (const btVector3 *a, const btVector3 *b)
 
btScalar btVec3PointSegmentDist2 (const btVector3 *P, const btVector3 *x0, const btVector3 *b, btVector3 *witness)
 
btScalar btVec3PointTriDist2 (const btVector3 *P, const btVector3 *x0, const btVector3 *B, const btVector3 *C, btVector3 *witness)
 
void btVec3Scale (btVector3 *d, btScalar k)
 
void btVec3Sub2 (btVector3 *d, const btVector3 *v, const btVector3 *w)
 
void calculateContinuousData (ContactResult *col, const btCollisionObjectWrapper *cow, const btVector3 &pt_world, const btVector3 &normal_world, const btTransform &link_tf_inv, size_t link_index)
 Calculate the continuous contact data for casted collision shape. More...
 
static SIMD_FORCE_INLINE btScalar capsuleCapsuleDistance (btVector3 &normalOnB, btVector3 &pointOnB, btScalar capsuleLengthA, btScalar capsuleRadiusA, btScalar capsuleLengthB, btScalar capsuleRadiusB, int capsuleAxisA, int capsuleAxisB, const btTransform &transformA, const btTransform &transformB, btScalar distanceThreshold)
 
static const btVector3 ccd_vec3_origin (0, 0, 0)
 
int ccdEq (btScalar _a, btScalar _b)
 
int ccdSign (btScalar val)
 
const btSupportVectorccdSimplexLast (const btSimplex *s)
 
void ccdVec3Add (btVector3 *v, const btVector3 *w)
 
btScalar ccdVec3Dist2 (const btVector3 *a, const btVector3 *b)
 
void ccdVec3Sub (btVector3 *v, const btVector3 *w)
 
btScalar ccdVec3X (const btVector3 *v)
 
btScalar ccdVec3Y (const btVector3 *v)
 
btScalar ccdVec3Z (const btVector3 *v)
 
Eigen::Matrix3d convertBtToEigen (const btMatrix3x3 &r)
 
Eigen::Isometry3d convertBtToEigen (const btTransform &t)
 
Eigen::Vector3d convertBtToEigen (const btVector3 &v)
 
btTransform convertEigenToBt (const Eigen::Isometry3d &t)
 
btMatrix3x3 convertEigenToBt (const Eigen::Matrix3d &r)
 
btQuaternion convertEigenToBt (const Eigen::Quaterniond &q)
 
btVector3 convertEigenToBt (const Eigen::Vector3d &v)
 
COW::Ptr createCollisionObject (const std::string &name, const int &type_id, const CollisionShapesConst &shapes, const tesseract_common::VectorIsometry3d &shape_poses, bool enabled=true)
 
std::shared_ptr< BulletCollisionShapecreateShapePrimitive (const CollisionShapeConstPtr &geom)
 Create a bullet collision shape from tesseract collision shape. More...
 
std::shared_ptr< BulletCollisionShapecreateShapePrimitive (const tesseract_geometry::Box::ConstPtr &geom)
 
std::shared_ptr< BulletCollisionShapecreateShapePrimitive (const tesseract_geometry::Capsule::ConstPtr &geom)
 
std::shared_ptr< BulletCollisionShapecreateShapePrimitive (const tesseract_geometry::CompoundMesh::ConstPtr &geom)
 
std::shared_ptr< BulletCollisionShapecreateShapePrimitive (const tesseract_geometry::Cone::ConstPtr &geom)
 
std::shared_ptr< BulletCollisionShapecreateShapePrimitive (const tesseract_geometry::ConvexMesh::ConstPtr &geom)
 
std::shared_ptr< BulletCollisionShapecreateShapePrimitive (const tesseract_geometry::Cylinder::ConstPtr &geom)
 
std::shared_ptr< BulletCollisionShapecreateShapePrimitive (const tesseract_geometry::Mesh::ConstPtr &geom)
 
std::shared_ptr< BulletCollisionShapecreateShapePrimitive (const tesseract_geometry::Octree::ConstPtr &geom)
 
std::shared_ptr< BulletCollisionShapecreateShapePrimitive (const tesseract_geometry::Sphere::ConstPtr &geom)
 
void GetAverageSupport (const btConvexShape *shape, const btVector3 &localNormal, btScalar &outsupport, btVector3 &outpt)
 
TesseractCollisionConfigurationInfo getConfigInfo (const YAML::Node &config)
 
btTransform getLinkTransformFromCOW (const btCollisionObjectWrapper *cow)
 This transversus the parent tree to find the base object and return its world transform This should be the links transform and it should only need to transverse twice at max. More...
 
COW::Ptr makeCastCollisionObject (const COW::Ptr &cow)
 
static void MycollideTT (const btDbvtNode *root0, const btDbvtNode *root1, const btTransform &xform, TesseractCompoundCompoundLeafCallback *callback, btScalar distanceThreshold)
 
static DBVT_INLINE bool MyIntersect (const btDbvtAabbMm &a, const btDbvtAabbMm &b, const btTransform &xform, btScalar distanceThreshold)
 
bool needsCollisionCheck (const COW &cow1, const COW &cow2, const std::shared_ptr< const tesseract_common::ContactAllowedValidator > &validator, bool verbose=false)
 This is used to check if a collision check is required between the provided two collision objects. More...
 
void refreshBroadphaseProxy (const COW::Ptr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
 Refresh the broadphase data structure. More...
 
void removeCollisionObjectFromBroadphase (const COW::Ptr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
 Remove the collision object from broadphase. More...
 
static SIMD_FORCE_INLINE void segmentsClosestPoints (btVector3 &ptsVector, btVector3 &offsetA, btVector3 &offsetB, btScalar &tA, btScalar &tB, const btVector3 &translation, const btVector3 &dirA, btScalar hlenA, const btVector3 &dirB, btScalar hlenB)
 
void updateBroadphaseAABB (const COW::Ptr &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, const COW::Ptr &cow)
 Update a collision objects filters. More...
 
void updateCollisionObjectFilters (const std::vector< std::string > &active, const COW::Ptr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
 Update a collision objects filters for broadphase. More...
 

Variables

const bool BULLET_COMPOUND_USE_DYNAMIC_AABB = true
 
const btScalar BULLET_DEFAULT_CONTACT_DISTANCE = btScalar(0.05)
 
const btScalar BULLET_EPSILON = btScalar(1e-3)
 
const btScalar BULLET_LENGTH_TOLERANCE = btScalar(0.001) METERS
 
const btScalar BULLET_MARGIN = btScalar(0.0)
 
const btScalar BULLET_SUPPORT_FUNC_TOLERANCE = btScalar(0.01) METERS
 
static const bool disableCcd = false
 
static const CollisionShapesConst EMPTY_COLLISION_SHAPES_CONST
 
static const CollisionShapesConst EMPTY_COLLISION_SHAPES_CONST
 
static const CollisionShapesConst EMPTY_COLLISION_SHAPES_CONST
 
static const CollisionShapesConst EMPTY_COLLISION_SHAPES_CONST
 
static const tesseract_common::VectorIsometry3d EMPTY_COLLISION_SHAPES_TRANSFORMS
 
static const tesseract_common::VectorIsometry3d EMPTY_COLLISION_SHAPES_TRANSFORMS
 
static const tesseract_common::VectorIsometry3d EMPTY_COLLISION_SHAPES_TRANSFORMS
 
static const tesseract_common::VectorIsometry3d EMPTY_COLLISION_SHAPES_TRANSFORMS
 

Typedef Documentation

◆ COW

Definition at line 150 of file bullet_utils.h.

◆ Link2ConstCow

Definition at line 152 of file bullet_utils.h.

◆ Link2Cow

Definition at line 151 of file bullet_utils.h.

Function Documentation

◆ addCastSingleResult()

btScalar tesseract_collision::tesseract_collision_bullet::addCastSingleResult ( btManifoldPoint &  cp,
const btCollisionObjectWrapper *  colObj0Wrap,
int  index0,
const btCollisionObjectWrapper *  colObj1Wrap,
int  index1,
ContactTestData collisions 
)

Definition at line 850 of file bullet_utils.cpp.

◆ addCollisionObjectToBroadphase()

void tesseract_collision::tesseract_collision_bullet::addCollisionObjectToBroadphase ( const COW::Ptr cow,
const std::unique_ptr< btBroadphaseInterface > &  broadphase,
const std::unique_ptr< btCollisionDispatcher > &  dispatcher 
)

Add the collision object to broadphase.

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

Definition at line 1382 of file bullet_utils.cpp.

◆ addDiscreteSingleResult() [1/2]

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

◆ addDiscreteSingleResult() [2/2]

btScalar tesseract_collision::tesseract_collision_bullet::addDiscreteSingleResult ( btManifoldPoint &  cp,
const btCollisionObjectWrapper *  colObj0Wrap,
int  index0,
const btCollisionObjectWrapper *  colObj1Wrap,
int  index1,
ContactTestData collisions 
)

Definition at line 710 of file bullet_utils.cpp.

◆ btComputeSupport()

static void tesseract_collision::tesseract_collision_bullet::btComputeSupport ( const btConvexShape *  convexA,
const btTransform &  localTransA,
const btConvexShape *  convexB,
const btTransform &  localTransB,
const btVector3 &  dir,
bool  check2d,
btVector3 &  supAworld,
btVector3 &  supBworld,
btVector3 &  aMinb 
)
static

Definition at line 103 of file tesseract_gjk_pair_detector.cpp.

◆ btDoSimplex()

static int tesseract_collision::tesseract_collision_bullet::btDoSimplex ( btSimplex simplex,
btVector3 *  dir 
)
static

Definition at line 644 of file tesseract_gjk_pair_detector.cpp.

◆ btDoSimplex2()

static int tesseract_collision::tesseract_collision_bullet::btDoSimplex2 ( btSimplex simplex,
btVector3 *  dir 
)
static

Definition at line 401 of file tesseract_gjk_pair_detector.cpp.

◆ btDoSimplex3()

static int tesseract_collision::tesseract_collision_bullet::btDoSimplex3 ( btSimplex simplex,
btVector3 *  dir 
)
static

Definition at line 445 of file tesseract_gjk_pair_detector.cpp.

◆ btDoSimplex4()

static int tesseract_collision::tesseract_collision_bullet::btDoSimplex4 ( btSimplex simplex,
btVector3 *  dir 
)
static

Definition at line 552 of file tesseract_gjk_pair_detector.cpp.

◆ btSimplexAdd()

void tesseract_collision::tesseract_collision_bullet::btSimplexAdd ( btSimplex s,
const btSupportVector v 
)
inline

Definition at line 235 of file tesseract_gjk_pair_detector.cpp.

◆ btSimplexInit()

void tesseract_collision::tesseract_collision_bullet::btSimplexInit ( btSimplex s)
inline

Definition at line 149 of file tesseract_gjk_pair_detector.cpp.

◆ btSimplexPoint()

const btSupportVector* tesseract_collision::tesseract_collision_bullet::btSimplexPoint ( const btSimplex s,
int  idx 
)
inline

Definition at line 153 of file tesseract_gjk_pair_detector.cpp.

◆ btSimplexSet()

void tesseract_collision::tesseract_collision_bullet::btSimplexSet ( btSimplex s,
size_t  pos,
const btSupportVector a 
)
inline

Definition at line 242 of file tesseract_gjk_pair_detector.cpp.

◆ btSimplexSetSize()

void tesseract_collision::tesseract_collision_bullet::btSimplexSetSize ( btSimplex s,
int  size 
)
inline

Definition at line 244 of file tesseract_gjk_pair_detector.cpp.

◆ btSimplexSize()

int tesseract_collision::tesseract_collision_bullet::btSimplexSize ( const btSimplex s)
inline

Definition at line 151 of file tesseract_gjk_pair_detector.cpp.

◆ btSupportCopy()

void tesseract_collision::tesseract_collision_bullet::btSupportCopy ( btSupportVector d,
const btSupportVector s 
)
inline

Definition at line 158 of file tesseract_gjk_pair_detector.cpp.

◆ btTripleCross()

void tesseract_collision::tesseract_collision_bullet::btTripleCross ( const btVector3 *  a,
const btVector3 *  b,
const btVector3 *  c,
btVector3 *  d 
)
inline

Definition at line 199 of file tesseract_gjk_pair_detector.cpp.

◆ btVec3Copy()

void tesseract_collision::tesseract_collision_bullet::btVec3Copy ( btVector3 *  v,
const btVector3 *  w 
)
inline

Definition at line 160 of file tesseract_gjk_pair_detector.cpp.

◆ btVec3Cross()

void tesseract_collision::tesseract_collision_bullet::btVec3Cross ( btVector3 *  d,
const btVector3 *  a,
const btVector3 *  b 
)
inline

Definition at line 192 of file tesseract_gjk_pair_detector.cpp.

◆ btVec3Dot()

btScalar tesseract_collision::tesseract_collision_bullet::btVec3Dot ( const btVector3 *  a,
const btVector3 *  b 
)
inline

Definition at line 171 of file tesseract_gjk_pair_detector.cpp.

◆ btVec3Eq()

int tesseract_collision::tesseract_collision_bullet::btVec3Eq ( const btVector3 *  a,
const btVector3 *  b 
)
inline

Definition at line 229 of file tesseract_gjk_pair_detector.cpp.

◆ btVec3PointSegmentDist2()

btScalar tesseract_collision::tesseract_collision_bullet::btVec3PointSegmentDist2 ( const btVector3 *  P,
const btVector3 *  x0,
const btVector3 *  b,
btVector3 *  witness 
)
inline

Definition at line 261 of file tesseract_gjk_pair_detector.cpp.

◆ btVec3PointTriDist2()

btScalar tesseract_collision::tesseract_collision_bullet::btVec3PointTriDist2 ( const btVector3 *  P,
const btVector3 *  x0,
const btVector3 *  B,
const btVector3 *  C,
btVector3 *  witness 
)

Definition at line 324 of file tesseract_gjk_pair_detector.cpp.

◆ btVec3Scale()

void tesseract_collision::tesseract_collision_bullet::btVec3Scale ( btVector3 *  d,
btScalar  k 
)
inline

Definition at line 185 of file tesseract_gjk_pair_detector.cpp.

◆ btVec3Sub2()

void tesseract_collision::tesseract_collision_bullet::btVec3Sub2 ( btVector3 *  d,
const btVector3 *  v,
const btVector3 *  w 
)
inline

Definition at line 170 of file tesseract_gjk_pair_detector.cpp.

◆ calculateContinuousData()

void tesseract_collision::tesseract_collision_bullet::calculateContinuousData ( ContactResult col,
const btCollisionObjectWrapper *  cow,
const btVector3 &  pt_world,
const btVector3 &  normal_world,
const btTransform &  link_tf_inv,
size_t  link_index 
)

Calculate the continuous contact data for casted collision shape.

Parameters
colContact results
cowBullet Collision Object Wrapper
pt_worldCasted contact point in world coordinates
normal_worldCasted normal to move shape out of collision in world coordinates
link_tf_invThe links world transform inverse
link_indexThe link index in teh ContactResults the shape is associated with

Definition at line 774 of file bullet_utils.cpp.

◆ capsuleCapsuleDistance()

static SIMD_FORCE_INLINE btScalar tesseract_collision::tesseract_collision_bullet::capsuleCapsuleDistance ( btVector3 &  normalOnB,
btVector3 &  pointOnB,
btScalar  capsuleLengthA,
btScalar  capsuleRadiusA,
btScalar  capsuleLengthB,
btScalar  capsuleRadiusB,
int  capsuleAxisA,
int  capsuleAxisB,
const btTransform &  transformA,
const btTransform &  transformB,
btScalar  distanceThreshold 
)
static

Definition at line 128 of file tesseract_convex_convex_algorithm.cpp.

◆ ccd_vec3_origin()

static const btVector3 tesseract_collision::tesseract_collision_bullet::ccd_vec3_origin ( ,
,
 
)
static

◆ ccdEq()

int tesseract_collision::tesseract_collision_bullet::ccdEq ( btScalar  _a,
btScalar  _b 
)
inline

Definition at line 206 of file tesseract_gjk_pair_detector.cpp.

◆ ccdSign()

int tesseract_collision::tesseract_collision_bullet::ccdSign ( btScalar  val)
inline

Definition at line 248 of file tesseract_gjk_pair_detector.cpp.

◆ ccdSimplexLast()

const btSupportVector* tesseract_collision::tesseract_collision_bullet::ccdSimplexLast ( const btSimplex s)
inline

Definition at line 246 of file tesseract_gjk_pair_detector.cpp.

◆ ccdVec3Add()

void tesseract_collision::tesseract_collision_bullet::ccdVec3Add ( btVector3 *  v,
const btVector3 *  w 
)
inline

Definition at line 162 of file tesseract_gjk_pair_detector.cpp.

◆ ccdVec3Dist2()

btScalar tesseract_collision::tesseract_collision_bullet::ccdVec3Dist2 ( const btVector3 *  a,
const btVector3 *  b 
)
inline

Definition at line 178 of file tesseract_gjk_pair_detector.cpp.

◆ ccdVec3Sub()

void tesseract_collision::tesseract_collision_bullet::ccdVec3Sub ( btVector3 *  v,
const btVector3 *  w 
)
inline

Definition at line 169 of file tesseract_gjk_pair_detector.cpp.

◆ ccdVec3X()

btScalar tesseract_collision::tesseract_collision_bullet::ccdVec3X ( const btVector3 *  v)

Definition at line 224 of file tesseract_gjk_pair_detector.cpp.

◆ ccdVec3Y()

btScalar tesseract_collision::tesseract_collision_bullet::ccdVec3Y ( const btVector3 *  v)

Definition at line 226 of file tesseract_gjk_pair_detector.cpp.

◆ ccdVec3Z()

btScalar tesseract_collision::tesseract_collision_bullet::ccdVec3Z ( const btVector3 *  v)

Definition at line 228 of file tesseract_gjk_pair_detector.cpp.

◆ convertBtToEigen() [1/3]

Eigen::Matrix3d tesseract_collision::tesseract_collision_bullet::convertBtToEigen ( const btMatrix3x3 &  r)

Definition at line 87 of file bullet_utils.cpp.

◆ convertBtToEigen() [2/3]

Eigen::Isometry3d tesseract_collision::tesseract_collision_bullet::convertBtToEigen ( const btTransform &  t)

Definition at line 104 of file bullet_utils.cpp.

◆ convertBtToEigen() [3/3]

Eigen::Vector3d tesseract_collision::tesseract_collision_bullet::convertBtToEigen ( const btVector3 &  v)

Definition at line 67 of file bullet_utils.cpp.

◆ convertEigenToBt() [1/4]

btTransform tesseract_collision::tesseract_collision_bullet::convertEigenToBt ( const Eigen::Isometry3d &  t)

Definition at line 96 of file bullet_utils.cpp.

◆ convertEigenToBt() [2/4]

btMatrix3x3 tesseract_collision::tesseract_collision_bullet::convertEigenToBt ( const Eigen::Matrix3d r)

Definition at line 80 of file bullet_utils.cpp.

◆ convertEigenToBt() [3/4]

btQuaternion tesseract_collision::tesseract_collision_bullet::convertEigenToBt ( const Eigen::Quaterniond q)

Definition at line 72 of file bullet_utils.cpp.

◆ convertEigenToBt() [4/4]

btVector3 tesseract_collision::tesseract_collision_bullet::convertEigenToBt ( const Eigen::Vector3d v)

Definition at line 62 of file bullet_utils.cpp.

◆ createCollisionObject()

COW::Ptr tesseract_collision::tesseract_collision_bullet::createCollisionObject ( const std::string &  name,
const int &  type_id,
const CollisionShapesConst shapes,
const tesseract_common::VectorIsometry3d shape_poses,
bool  enabled = true 
)

Definition at line 1161 of file bullet_utils.cpp.

◆ createShapePrimitive() [1/10]

std::shared_ptr< BulletCollisionShape > tesseract_collision::tesseract_collision_bullet::createShapePrimitive ( const CollisionShapeConstPtr geom)

Create a bullet collision shape from tesseract collision shape.

Parameters
geomTesseract collision shape
Returns
Bullet collision shape.

Definition at line 366 of file bullet_utils.cpp.

◆ createShapePrimitive() [2/10]

std::shared_ptr<BulletCollisionShape> tesseract_collision::tesseract_collision_bullet::createShapePrimitive ( const tesseract_geometry::Box::ConstPtr geom)

Definition at line 113 of file bullet_utils.cpp.

◆ createShapePrimitive() [3/10]

std::shared_ptr<BulletCollisionShape> tesseract_collision::tesseract_collision_bullet::createShapePrimitive ( const tesseract_geometry::Capsule::ConstPtr geom)

Definition at line 142 of file bullet_utils.cpp.

◆ createShapePrimitive() [4/10]

std::shared_ptr<BulletCollisionShape> tesseract_collision::tesseract_collision_bullet::createShapePrimitive ( const tesseract_geometry::CompoundMesh::ConstPtr geom)

Definition at line 340 of file bullet_utils.cpp.

◆ createShapePrimitive() [5/10]

std::shared_ptr<BulletCollisionShape> tesseract_collision::tesseract_collision_bullet::createShapePrimitive ( const tesseract_geometry::Cone::ConstPtr geom)

Definition at line 135 of file bullet_utils.cpp.

◆ createShapePrimitive() [6/10]

std::shared_ptr<BulletCollisionShape> tesseract_collision::tesseract_collision_bullet::createShapePrimitive ( const tesseract_geometry::ConvexMesh::ConstPtr geom)

Definition at line 194 of file bullet_utils.cpp.

◆ createShapePrimitive() [7/10]

std::shared_ptr<BulletCollisionShape> tesseract_collision::tesseract_collision_bullet::createShapePrimitive ( const tesseract_geometry::Cylinder::ConstPtr geom)

Definition at line 128 of file bullet_utils.cpp.

◆ createShapePrimitive() [8/10]

std::shared_ptr<BulletCollisionShape> tesseract_collision::tesseract_collision_bullet::createShapePrimitive ( const tesseract_geometry::Mesh::ConstPtr geom)

Definition at line 149 of file bullet_utils.cpp.

◆ createShapePrimitive() [9/10]

std::shared_ptr<BulletCollisionShape> tesseract_collision::tesseract_collision_bullet::createShapePrimitive ( const tesseract_geometry::Octree::ConstPtr geom)

Definition at line 213 of file bullet_utils.cpp.

◆ createShapePrimitive() [10/10]

std::shared_ptr<BulletCollisionShape> tesseract_collision::tesseract_collision_bullet::createShapePrimitive ( const tesseract_geometry::Sphere::ConstPtr geom)

Definition at line 122 of file bullet_utils.cpp.

◆ GetAverageSupport()

void tesseract_collision::tesseract_collision_bullet::GetAverageSupport ( const btConvexShape *  shape,
const btVector3 &  localNormal,
btScalar &  outsupport,
btVector3 &  outpt 
)

Definition at line 640 of file bullet_utils.cpp.

◆ getConfigInfo()

TesseractCollisionConfigurationInfo tesseract_collision::tesseract_collision_bullet::getConfigInfo ( const YAML::Node &  config)

Definition at line 44 of file bullet_factories.cpp.

◆ getLinkTransformFromCOW()

btTransform tesseract_collision::tesseract_collision_bullet::getLinkTransformFromCOW ( const btCollisionObjectWrapper *  cow)

This transversus the parent tree to find the base object and return its world transform This should be the links transform and it should only need to transverse twice at max.

Parameters
cowBullet collision object wrapper.
Returns
Transform of link in world coordinates

Definition at line 684 of file bullet_utils.cpp.

◆ makeCastCollisionObject()

COW::Ptr tesseract_collision::tesseract_collision_bullet::makeCastCollisionObject ( const COW::Ptr cow)

Definition at line 1249 of file bullet_utils.cpp.

◆ MycollideTT()

static void tesseract_collision::tesseract_collision_bullet::MycollideTT ( const btDbvtNode *  root0,
const btDbvtNode *  root1,
const btTransform &  xform,
TesseractCompoundCompoundLeafCallback callback,
btScalar  distanceThreshold 
)
inlinestatic

◆ MyIntersect()

static DBVT_INLINE bool tesseract_collision::tesseract_collision_bullet::MyIntersect ( const btDbvtAabbMm &  a,
const btDbvtAabbMm &  b,
const btTransform &  xform,
btScalar  distanceThreshold 
)
static

◆ needsCollisionCheck()

bool tesseract_collision::tesseract_collision_bullet::needsCollisionCheck ( const COW cow1,
const COW cow2,
const std::shared_ptr< const tesseract_common::ContactAllowedValidator > &  validator,
bool  verbose = false 
)

This is used to check if a collision check is required between the provided two collision objects.

Parameters
cow1The first collision object
cow2The second collision object
validatorThe contact allowed validator
verboseIndicate if verbose information should be printed to the terminal
Returns
True if the two collision objects should be checked for collision, otherwise false

Definition at line 700 of file bullet_utils.cpp.

◆ refreshBroadphaseProxy()

void tesseract_collision::tesseract_collision_bullet::refreshBroadphaseProxy ( const COW::Ptr cow,
const std::unique_ptr< btBroadphaseInterface > &  broadphase,
const std::unique_ptr< btCollisionDispatcher > &  dispatcher 
)

Refresh the broadphase data structure.

When change certain properties of a collision object the broadphase is not aware so this function can be called to trigger an update. For example, when changing active links this changes internal flags which may require moving a collision object from the static BVH to the dynamic BVH so this function must be called.

Parameters
cowThe collision object to update.
broadphaseThe broadphase to update.
dispatcherThe dispatcher.

Definition at line 1408 of file bullet_utils.cpp.

◆ removeCollisionObjectFromBroadphase()

void tesseract_collision::tesseract_collision_bullet::removeCollisionObjectFromBroadphase ( const COW::Ptr cow,
const std::unique_ptr< btBroadphaseInterface > &  broadphase,
const std::unique_ptr< btCollisionDispatcher > &  dispatcher 
)

Remove the collision object from broadphase.

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

Definition at line 1368 of file bullet_utils.cpp.

◆ segmentsClosestPoints()

static SIMD_FORCE_INLINE void tesseract_collision::tesseract_collision_bullet::segmentsClosestPoints ( btVector3 &  ptsVector,
btVector3 &  offsetA,
btVector3 &  offsetB,
btScalar &  tA,
btScalar &  tB,
const btVector3 &  translation,
const btVector3 &  dirA,
btScalar  hlenA,
const btVector3 &  dirB,
btScalar  hlenB 
)
static

Definition at line 65 of file tesseract_convex_convex_algorithm.cpp.

◆ updateBroadphaseAABB()

void tesseract_collision::tesseract_collision_bullet::updateBroadphaseAABB ( const COW::Ptr cow,
const std::unique_ptr< btBroadphaseInterface > &  broadphase,
const std::unique_ptr< btCollisionDispatcher > &  dispatcher 
)

Update the Broadphase AABB for the input collision object.

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

Definition at line 1355 of file bullet_utils.cpp.

◆ updateCollisionObjectFilters() [1/2]

void tesseract_collision::tesseract_collision_bullet::updateCollisionObjectFilters ( const std::vector< std::string > &  active,
const COW::Ptr cow 
)

Update a collision objects filters.

Parameters
activeA list of active collision objects
cowThe collision object to update.

Definition at line 442 of file bullet_utils.cpp.

◆ updateCollisionObjectFilters() [2/2]

void tesseract_collision::tesseract_collision_bullet::updateCollisionObjectFilters ( const std::vector< std::string > &  active,
const COW::Ptr cow,
const std::unique_ptr< btBroadphaseInterface > &  broadphase,
const std::unique_ptr< btCollisionDispatcher > &  dispatcher 
)

Update a collision objects filters for broadphase.

Parameters
activeA list of active collision objects
cowThe collision object to update.
broadphaseThe collision object to update.
dispatcherThe collision object to update.

Definition at line 1395 of file bullet_utils.cpp.

Variable Documentation

◆ BULLET_COMPOUND_USE_DYNAMIC_AABB

const bool tesseract_collision::tesseract_collision_bullet::BULLET_COMPOUND_USE_DYNAMIC_AABB = true

Definition at line 67 of file bullet_utils.h.

◆ BULLET_DEFAULT_CONTACT_DISTANCE

const btScalar tesseract_collision::tesseract_collision_bullet::BULLET_DEFAULT_CONTACT_DISTANCE = btScalar(0.05)

Definition at line 66 of file bullet_utils.h.

◆ BULLET_EPSILON

const btScalar tesseract_collision::tesseract_collision_bullet::BULLET_EPSILON = btScalar(1e-3)

Definition at line 65 of file bullet_utils.h.

◆ BULLET_LENGTH_TOLERANCE

const btScalar tesseract_collision::tesseract_collision_bullet::BULLET_LENGTH_TOLERANCE = btScalar(0.001) METERS

Definition at line 64 of file bullet_utils.h.

◆ BULLET_MARGIN

const btScalar tesseract_collision::tesseract_collision_bullet::BULLET_MARGIN = btScalar(0.0)

Definition at line 62 of file bullet_utils.h.

◆ BULLET_SUPPORT_FUNC_TOLERANCE

const btScalar tesseract_collision::tesseract_collision_bullet::BULLET_SUPPORT_FUNC_TOLERANCE = btScalar(0.01) METERS

Definition at line 63 of file bullet_utils.h.

◆ disableCcd

const bool tesseract_collision::tesseract_collision_bullet::disableCcd = false
static

Definition at line 852 of file tesseract_convex_convex_algorithm.cpp.

◆ EMPTY_COLLISION_SHAPES_CONST [1/4]

const CollisionShapesConst tesseract_collision::tesseract_collision_bullet::EMPTY_COLLISION_SHAPES_CONST
static

Definition at line 47 of file bullet_cast_simple_manager.cpp.

◆ EMPTY_COLLISION_SHAPES_CONST [2/4]

const CollisionShapesConst tesseract_collision::tesseract_collision_bullet::EMPTY_COLLISION_SHAPES_CONST
static

Definition at line 47 of file bullet_discrete_simple_manager.cpp.

◆ EMPTY_COLLISION_SHAPES_CONST [3/4]

const CollisionShapesConst tesseract_collision::tesseract_collision_bullet::EMPTY_COLLISION_SHAPES_CONST
static

Definition at line 49 of file bullet_cast_bvh_manager.cpp.

◆ EMPTY_COLLISION_SHAPES_CONST [4/4]

const CollisionShapesConst tesseract_collision::tesseract_collision_bullet::EMPTY_COLLISION_SHAPES_CONST
static

Definition at line 49 of file bullet_discrete_bvh_manager.cpp.

◆ EMPTY_COLLISION_SHAPES_TRANSFORMS [1/4]

const tesseract_common::VectorIsometry3d tesseract_collision::tesseract_collision_bullet::EMPTY_COLLISION_SHAPES_TRANSFORMS
static

Definition at line 48 of file bullet_discrete_simple_manager.cpp.

◆ EMPTY_COLLISION_SHAPES_TRANSFORMS [2/4]

const tesseract_common::VectorIsometry3d tesseract_collision::tesseract_collision_bullet::EMPTY_COLLISION_SHAPES_TRANSFORMS
static

Definition at line 48 of file bullet_cast_simple_manager.cpp.

◆ EMPTY_COLLISION_SHAPES_TRANSFORMS [3/4]

const tesseract_common::VectorIsometry3d tesseract_collision::tesseract_collision_bullet::EMPTY_COLLISION_SHAPES_TRANSFORMS
static

Definition at line 50 of file bullet_cast_bvh_manager.cpp.

◆ EMPTY_COLLISION_SHAPES_TRANSFORMS [4/4]

const tesseract_common::VectorIsometry3d tesseract_collision::tesseract_collision_bullet::EMPTY_COLLISION_SHAPES_TRANSFORMS
static

Definition at line 50 of file bullet_discrete_bvh_manager.cpp.



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