Tesseract 0.28.4
Loading...
Searching...
No Matches
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/types.h>
#include <tesseract/collision/common.h>
#include <tesseract/collision/bullet/bullet_collision_shape_cache.h>

Classes

class  tesseract::collision::bullet_internal::CollisionObjectWrapper
 This is a tesseract bullet collsion object. More...
 
struct  tesseract::collision::bullet_internal::CastHullShape
 This is a casted collision shape used for checking if an object is collision free between two transforms. More...
 
struct  tesseract::collision::bullet_internal::TesseractBridgedManifoldResult
 This is copied directly out of BulletWorld. More...
 
struct  tesseract::collision::bullet_internal::BroadphaseContactResultCallback
 The BroadphaseContactResultCallback is used to report contact points. More...
 
struct  tesseract::collision::bullet_internal::DiscreteBroadphaseContactResultCallback
 
struct  tesseract::collision::bullet_internal::CastBroadphaseContactResultCallback
 
struct  tesseract::collision::bullet_internal::TesseractBroadphaseBridgedManifoldResult
 
class  tesseract::collision::bullet_internal::TesseractCollisionPairCallback
 A callback function that is called as part of the broadphase collision checking. More...
 
class  tesseract::collision::bullet_internal::TesseractOverlapFilterCallback
 This class is used to filter broadphase. More...
 
struct  tesseract::collision::bullet_internal::DiscreteCollisionCollector
 
struct  tesseract::collision::bullet_internal::CastCollisionCollector
 

Typedefs

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

Functions

btVector3 tesseract::collision::bullet_internal::convertEigenToBt (const Eigen::Vector3d &v)
 
Eigen::Vector3d tesseract::collision::bullet_internal::convertBtToEigen (const btVector3 &v)
 
btQuaternion tesseract::collision::bullet_internal::convertEigenToBt (const Eigen::Quaterniond &q)
 
btMatrix3x3 tesseract::collision::bullet_internal::convertEigenToBt (const Eigen::Matrix3d &r)
 
Eigen::Matrix3d tesseract::collision::bullet_internal::convertBtToEigen (const btMatrix3x3 &r)
 
btTransform tesseract::collision::bullet_internal::convertEigenToBt (const Eigen::Isometry3d &t)
 
Eigen::Isometry3d tesseract::collision::bullet_internal::convertBtToEigen (const btTransform &t)
 
void tesseract::collision::bullet_internal::GetAverageSupport (const btConvexShape *shape, const btVector3 &localNormal, btScalar &outsupport, btVector3 &outpt)
 
btTransform tesseract::collision::bullet_internal::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.
 
bool tesseract::collision::bullet_internal::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.
 
void tesseract::collision::bullet_internal::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.
 
std::shared_ptr< BulletCollisionShapetesseract::collision::bullet_internal::createShapePrimitive (const CollisionShapeConstPtr &geom)
 Create a bullet collision shape from tesseract collision shape.
 
void tesseract::collision::bullet_internal::updateCollisionObjectFilters (const std::vector< std::string > &active, const COW::Ptr &cow)
 Update a collision objects filters.
 
COW::Ptr tesseract::collision::bullet_internal::createCollisionObject (const std::string &name, const int &type_id, const CollisionShapesConst &shapes, const tesseract::common::VectorIsometry3d &shape_poses, bool enabled=true)
 
COW::Ptr tesseract::collision::bullet_internal::makeCastCollisionObject (const COW::Ptr &cow)
 
void tesseract::collision::bullet_internal::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.
 
void tesseract::collision::bullet_internal::removeCollisionObjectFromBroadphase (const COW::Ptr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
 Remove the collision object from broadphase.
 
void tesseract::collision::bullet_internal::addCollisionObjectToBroadphase (const COW::Ptr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
 Add the collision object to broadphase.
 
void tesseract::collision::bullet_internal::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.
 
void tesseract::collision::bullet_internal::refreshBroadphaseProxy (const COW::Ptr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
 Refresh the broadphase data structure.
 

Variables

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

Detailed Description

Tesseract ROS Bullet environment utility function.

Author
John Schulman
Levi Armstrong
Date
Dec 18, 2017
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.

Function Documentation

◆ getLinkTransformFromCOW()

btTransform tesseract::collision::bullet_internal::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

◆ needsCollisionCheck()

bool tesseract::collision::bullet_internal::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

◆ calculateContinuousData()

void tesseract::collision::bullet_internal::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

◆ createShapePrimitive()

std::shared_ptr< BulletCollisionShape > tesseract::collision::bullet_internal::createShapePrimitive ( const CollisionShapeConstPtr &  geom)

Create a bullet collision shape from tesseract collision shape.

Parameters
geomTesseract collision shape
Returns
Bullet collision shape.

◆ updateCollisionObjectFilters() [1/2]

void tesseract::collision::bullet_internal::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.

◆ updateBroadphaseAABB()

void tesseract::collision::bullet_internal::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

◆ removeCollisionObjectFromBroadphase()

void tesseract::collision::bullet_internal::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

◆ addCollisionObjectToBroadphase()

void tesseract::collision::bullet_internal::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

◆ updateCollisionObjectFilters() [2/2]

void tesseract::collision::bullet_internal::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.

◆ refreshBroadphaseProxy()

void tesseract::collision::bullet_internal::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.