Tesseract ROS Bullet environment utility function. More...
#include <tesseract_collision/bullet/bullet_utils.h>
#include <tesseract_collision/bullet/bullet_collision_shape_cache.h>
#include <LinearMath/btConvexHullComputer.h>
#include <BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h>
#include <BulletCollision/CollisionShapes/btShapeHull.h>
#include <BulletCollision/Gimpact/btTriangleShapeEx.h>
#include <boost/thread/mutex.hpp>
#include <memory>
#include <stdexcept>
#include <octomap/octomap.h>
#include <tesseract_geometry/geometries.h>
Go to the source code of this file.
Namespaces | |
tesseract_collision | |
tesseract_collision::tesseract_collision_bullet | |
Functions | |
btScalar | tesseract_collision::tesseract_collision_bullet::addCastSingleResult (btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int index0, const btCollisionObjectWrapper *colObj1Wrap, int index1, ContactTestData &collisions) |
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. More... | |
btScalar | tesseract_collision::tesseract_collision_bullet::addDiscreteSingleResult (btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, int index0, const btCollisionObjectWrapper *colObj1Wrap, int index1, ContactTestData &collisions) |
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. More... | |
Eigen::Matrix3d | tesseract_collision::tesseract_collision_bullet::convertBtToEigen (const btMatrix3x3 &r) |
Eigen::Isometry3d | tesseract_collision::tesseract_collision_bullet::convertBtToEigen (const btTransform &t) |
Eigen::Vector3d | tesseract_collision::tesseract_collision_bullet::convertBtToEigen (const btVector3 &v) |
btTransform | tesseract_collision::tesseract_collision_bullet::convertEigenToBt (const Eigen::Isometry3d &t) |
btMatrix3x3 | tesseract_collision::tesseract_collision_bullet::convertEigenToBt (const Eigen::Matrix3d &r) |
btQuaternion | tesseract_collision::tesseract_collision_bullet::convertEigenToBt (const Eigen::Quaterniond &q) |
btVector3 | tesseract_collision::tesseract_collision_bullet::convertEigenToBt (const Eigen::Vector3d &v) |
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) |
std::shared_ptr< BulletCollisionShape > | tesseract_collision::tesseract_collision_bullet::createShapePrimitive (const CollisionShapeConstPtr &geom) |
Create a bullet collision shape from tesseract collision shape. More... | |
std::shared_ptr< BulletCollisionShape > | tesseract_collision::tesseract_collision_bullet::createShapePrimitive (const tesseract_geometry::Box::ConstPtr &geom) |
std::shared_ptr< BulletCollisionShape > | tesseract_collision::tesseract_collision_bullet::createShapePrimitive (const tesseract_geometry::Capsule::ConstPtr &geom) |
std::shared_ptr< BulletCollisionShape > | tesseract_collision::tesseract_collision_bullet::createShapePrimitive (const tesseract_geometry::CompoundMesh::ConstPtr &geom) |
std::shared_ptr< BulletCollisionShape > | tesseract_collision::tesseract_collision_bullet::createShapePrimitive (const tesseract_geometry::Cone::ConstPtr &geom) |
std::shared_ptr< BulletCollisionShape > | tesseract_collision::tesseract_collision_bullet::createShapePrimitive (const tesseract_geometry::ConvexMesh::ConstPtr &geom) |
std::shared_ptr< BulletCollisionShape > | tesseract_collision::tesseract_collision_bullet::createShapePrimitive (const tesseract_geometry::Cylinder::ConstPtr &geom) |
std::shared_ptr< BulletCollisionShape > | tesseract_collision::tesseract_collision_bullet::createShapePrimitive (const tesseract_geometry::Mesh::ConstPtr &geom) |
std::shared_ptr< BulletCollisionShape > | tesseract_collision::tesseract_collision_bullet::createShapePrimitive (const tesseract_geometry::Octree::ConstPtr &geom) |
std::shared_ptr< BulletCollisionShape > | tesseract_collision::tesseract_collision_bullet::createShapePrimitive (const tesseract_geometry::Sphere::ConstPtr &geom) |
void | tesseract_collision::tesseract_collision_bullet::GetAverageSupport (const btConvexShape *shape, const btVector3 &localNormal, btScalar &outsupport, btVector3 &outpt) |
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. More... | |
COW::Ptr | tesseract_collision::tesseract_collision_bullet::makeCastCollisionObject (const COW::Ptr &cow) |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
void | tesseract_collision::tesseract_collision_bullet::updateCollisionObjectFilters (const std::vector< std::string > &active, const COW::Ptr &cow) |
Update a collision objects filters. More... | |
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. More... | |
Tesseract ROS Bullet environment utility function.
Definition in file bullet_utils.cpp.