| 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::Contact * | processResult (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 | 
| 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.
| 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.
| using collision_detection_bullet::AlignedVector = typedef std::vector<T, Eigen::aligned_allocator<T> > | 
Definition at line 53 of file basic_types.h.
| 
 | strong | 
| 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.
| 
 | inline | 
Allowed = true.
Definition at line 91 of file bullet_utils.h.
| 
 | inline | 
Definition at line 486 of file bullet_utils.h.
| 
 | inline | 
Add the collision object to broadphase.
| cow | The collision objects | 
| broadphase | The bullet broadphase interface | 
| dispatcher | The bullet collision dispatcher | 
Definition at line 949 of file bullet_utils.h.
| 
 | 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.
| 
 | inline | 
Definition at line 78 of file ros_bullet_utils.h.
| 
 | inline | 
Converts bullet vector to eigen vector.
Definition at line 135 of file bullet_utils.h.
| 
 | inline | 
Converts bullet transform to eigen transform.
Definition at line 156 of file bullet_utils.h.
| 
 | inline | 
Converts eigen matrix to bullet matrix.
Definition at line 148 of file bullet_utils.h.
| 
 | inline | 
Converts eigen quaternion to bullet quaternion.
Definition at line 141 of file bullet_utils.h.
| 
 | inline | 
Converts eigen vector to bullet vector.
Definition at line 129 of file bullet_utils.h.
| 
 | inline | 
Create a convex hull from vertices using Bullet Convex Hull Computer.
| (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. | 
Definition at line 166 of file contact_checker_common.h.
| btCollisionShape* collision_detection_bullet::createShapePrimitive | ( | const shapes::Box * | geom, | 
| const CollisionObjectType & | collision_object_type | ||
| ) | 
Definition at line 77 of file bullet_utils.cpp.
| btCollisionShape* collision_detection_bullet::createShapePrimitive | ( | const shapes::Cone * | geom, | 
| const CollisionObjectType & | collision_object_type | ||
| ) | 
Definition at line 105 of file bullet_utils.cpp.
| btCollisionShape* collision_detection_bullet::createShapePrimitive | ( | const shapes::Cylinder * | geom, | 
| const CollisionObjectType & | collision_object_type | ||
| ) | 
Definition at line 96 of file bullet_utils.cpp.
| 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.
| 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.
| 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.
| btCollisionShape* collision_detection_bullet::createShapePrimitive | ( | const shapes::Sphere * | geom, | 
| const CollisionObjectType & | collision_object_type | ||
| ) | 
Definition at line 89 of file bullet_utils.cpp.
| 
 | inlinestatic | 
Recursively traverses robot from root to get all active links.
| active_links | Stores the active links | 
| urdf_link | The current urdf link representation | 
| active | Indicates if link is considered active | 
Definition at line 54 of file ros_bullet_utils.h.
| 
 | inline | 
Computes the local supporting vertex of a convex shape.
If multiple vertices with equal support products exists, their average is calculated and returned.
| shape | The convex shape to check | 
| localNormal | The support direction to search for in shape local coordinates | 
| outsupport | The value of the calculated support mapping | 
| outpt | The computed support point | 
Definition at line 409 of file bullet_utils.h.
| 
 | inline | 
Get a key for two object to search the collision matrix.
| obj1 | First collision object name | 
| obj2 | Second collision object name | 
Definition at line 56 of file contact_checker_common.h.
| 
 | inline | 
This will check if a link is active provided a list. If the list is empty the link is considered active.
| active | List of active link names | 
| name | The name of link to check if it is active. | 
Definition at line 66 of file contact_checker_common.h.
| 
 | inline | 
Checks if the collision pair is kinematic vs kinematic objects.
Definition at line 587 of file bullet_utils.h.
| 
 | inline | 
Definition at line 818 of file bullet_utils.h.
| collision_detection_bullet::MOVEIT_CLASS_FORWARD | ( | BulletBVHManager | ) | 
| collision_detection_bullet::MOVEIT_CLASS_FORWARD | ( | BulletCastBVHManager | ) | 
| collision_detection_bullet::MOVEIT_CLASS_FORWARD | ( | BulletDiscreteBVHManager | ) | 
| collision_detection_bullet::MOVEIT_CLASS_FORWARD | ( | CollisionObjectWrapper | ) | 
| 
 | inline | 
Stores a single contact result in the requested way.
| found | Indicates if a contact for this pair of objects has already been found | 
Definition at line 74 of file contact_checker_common.h.
| 
 | inline | 
Remove the collision object from broadphase.
| cow | The collision objects | 
| broadphase | The bullet broadphase interface | 
| dispatcher | The bullet collision dispatcher | 
Definition at line 931 of file bullet_utils.h.
| 
 | inline | 
Update the Broadphase AABB for the input collision object.
| cow | The collision objects | 
| broadphase | The bullet broadphase interface | 
| dispatcher | The bullet collision dispatcher | 
Definition at line 916 of file bullet_utils.h.
| 
 | inline | 
Update a collision objects filters.
| active | A list of active collision objects | 
| cow | The collision object to update. | 
| continuous | Indicate 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.
| 
 | inline | 
Definition at line 115 of file ros_bullet_utils.h.
| const bool collision_detection_bullet::BULLET_COMPOUND_USE_DYNAMIC_AABB = true | 
Definition at line 86 of file bullet_utils.h.
| const btScalar collision_detection_bullet::BULLET_DEFAULT_CONTACT_DISTANCE = 0.00f | 
Definition at line 85 of file bullet_utils.h.
| const btScalar collision_detection_bullet::BULLET_EPSILON = 1e-3f | 
Definition at line 84 of file bullet_utils.h.
Definition at line 83 of file bullet_utils.h.
| const btScalar collision_detection_bullet::BULLET_MARGIN = 0.0f | 
Definition at line 81 of file bullet_utils.h.
Definition at line 82 of file bullet_utils.h.