Classes | Namespaces | Macros | Typedefs | Functions | Variables
bullet_utils.h File Reference

Tesseract ROS Bullet environment utility function. More...

#include <tesseract_common/macros.h>
#include <BulletCollision/CollisionShapes/btCollisionShape.h>
#include <BulletCollision/CollisionDispatch/btManifoldResult.h>
#include <btBulletCollisionCommon.h>
#include <console_bridge/console.h>
#include <tesseract_collision/core/types.h>
#include <tesseract_collision/core/common.h>
#include <tesseract_collision/bullet/bullet_collision_shape_cache.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  tesseract_collision::tesseract_collision_bullet::BroadphaseContactResultCallback
 The BroadphaseContactResultCallback is used to report contact points. More...
 
struct  tesseract_collision::tesseract_collision_bullet::CastBroadphaseContactResultCallback
 
struct  tesseract_collision::tesseract_collision_bullet::CastCollisionCollector
 
struct  tesseract_collision::tesseract_collision_bullet::CastHullShape
 This is a casted collision shape used for checking if an object is collision free between two transforms. More...
 
class  tesseract_collision::tesseract_collision_bullet::CollisionObjectWrapper
 This is a tesseract bullet collsion object. More...
 
struct  tesseract_collision::tesseract_collision_bullet::DiscreteBroadphaseContactResultCallback
 
struct  tesseract_collision::tesseract_collision_bullet::DiscreteCollisionCollector
 
struct  tesseract_collision::tesseract_collision_bullet::TesseractBridgedManifoldResult
 This is copied directly out of BulletWorld. More...
 
struct  tesseract_collision::tesseract_collision_bullet::TesseractBroadphaseBridgedManifoldResult
 
class  tesseract_collision::tesseract_collision_bullet::TesseractCollisionPairCallback
 A callback function that is called as part of the broadphase collision checking. More...
 
class  tesseract_collision::tesseract_collision_bullet::TesseractOverlapFilterCallback
 This class is used to filter broadphase. More...
 

Namespaces

 tesseract_collision
 
 tesseract_collision::tesseract_collision_bullet
 

Macros

#define METERS
 

Typedefs

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

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, const btCollisionObjectWrapper *colObj1Wrap, 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...
 
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...
 

Variables

const bool tesseract_collision::tesseract_collision_bullet::BULLET_COMPOUND_USE_DYNAMIC_AABB = true
 
const btScalar tesseract_collision::tesseract_collision_bullet::BULLET_DEFAULT_CONTACT_DISTANCE = btScalar(0.05)
 
const btScalar tesseract_collision::tesseract_collision_bullet::BULLET_EPSILON = btScalar(1e-3)
 
const btScalar tesseract_collision::tesseract_collision_bullet::BULLET_LENGTH_TOLERANCE = btScalar(0.001) METERS
 
const btScalar tesseract_collision::tesseract_collision_bullet::BULLET_MARGIN = btScalar(0.0)
 
const btScalar tesseract_collision::tesseract_collision_bullet::BULLET_SUPPORT_FUNC_TOLERANCE = btScalar(0.01) METERS
 

Detailed Description

Tesseract ROS Bullet environment utility function.

Author
John Schulman
Levi Armstrong
Date
Dec 18, 2017
Version
TODO
Bug:
No known bugs
License
Software License Agreement (BSD-2-Clause)
All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
  • Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
  • Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Definition in file bullet_utils.h.

Macro Definition Documentation

◆ METERS

#define METERS

Definition at line 60 of file bullet_utils.h.



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