Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager Class Reference

A simple implementation of a tesseract manager which does not use BHV. More...

#include <bullet_cast_simple_manager.h>

Inheritance diagram for tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager:
Inheritance graph
[legend]

Public Types

using ConstPtr = std::shared_ptr< const BulletCastSimpleManager >
 
using ConstUPtr = std::unique_ptr< const BulletCastSimpleManager >
 
using Ptr = std::shared_ptr< BulletCastSimpleManager >
 
using UPtr = std::unique_ptr< BulletCastSimpleManager >
 
- Public Types inherited from tesseract_collision::ContinuousContactManager
using ConstPtr = std::shared_ptr< const ContinuousContactManager >
 
using ConstUPtr = std::unique_ptr< const ContinuousContactManager >
 
using Ptr = std::shared_ptr< ContinuousContactManager >
 
using UPtr = std::unique_ptr< ContinuousContactManager >
 

Public Member Functions

void addCollisionObject (const COW::Ptr &cow)
 A a bullet collision object to the manager. More...
 
bool addCollisionObject (const std::string &name, const int &mask_id, const CollisionShapesConst &shapes, const tesseract_common::VectorIsometry3d &shape_poses, bool enabled=true) override final
 Add a collision object to the checker. More...
 
 BulletCastSimpleManager (BulletCastSimpleManager &&)=delete
 
 BulletCastSimpleManager (const BulletCastSimpleManager &)=delete
 
 BulletCastSimpleManager (std::string name="BulletCastSimpleManager", TesseractCollisionConfigurationInfo config_info=TesseractCollisionConfigurationInfo())
 
ContinuousContactManager::UPtr clone () const override final
 Clone the manager. More...
 
void contactTest (ContactResultMap &collisions, const ContactRequest &request) override final
 Perform a contact test for all objects based. More...
 
bool disableCollisionObject (const std::string &name) override final
 Disable an object. More...
 
bool enableCollisionObject (const std::string &name) override final
 Enable an object. More...
 
const std::vector< std::string > & getActiveCollisionObjects () const override final
 Get which collision objects can move. More...
 
const CollisionMarginDatagetCollisionMarginData () const override final
 Get the contact distance threshold. More...
 
const CollisionShapesConstgetCollisionObjectGeometries (const std::string &name) const override final
 Get a collision objects collision geometries. More...
 
const tesseract_common::VectorIsometry3dgetCollisionObjectGeometriesTransforms (const std::string &name) const override final
 Get a collision objects collision geometries transforms. More...
 
const std::vector< std::string > & getCollisionObjects () const override final
 Get all collision objects. More...
 
std::shared_ptr< const tesseract_common::ContactAllowedValidatorgetContactAllowedValidator () const override final
 Get the active function for determining if two links are allowed to be in collision. More...
 
std::string getName () const override final
 Get the name of the contact manager. More...
 
bool hasCollisionObject (const std::string &name) const override final
 Find if a collision object already exists. More...
 
void incrementCollisionMargin (double increment) override final
 Increment the collision margin data by some value. More...
 
bool isCollisionObjectEnabled (const std::string &name) const override final
 Check if collision object is enabled. More...
 
BulletCastSimpleManageroperator= (BulletCastSimpleManager &&)=delete
 
BulletCastSimpleManageroperator= (const BulletCastSimpleManager &)=delete
 
bool removeCollisionObject (const std::string &name) override final
 Remove an object from the checker. More...
 
void setActiveCollisionObjects (const std::vector< std::string > &names) override final
 Set which collision objects can move. More...
 
void setCollisionMarginData (CollisionMarginData collision_margin_data) override final
 Set the contact distance threshold. More...
 
void setCollisionMarginPair (const std::string &name1, const std::string &name2, double collision_margin) override final
 Set the margin for a given contact pair. More...
 
void setCollisionMarginPairData (const CollisionMarginPairData &pair_margin_data, CollisionMarginPairOverrideType override_type=CollisionMarginPairOverrideType::REPLACE) override final
 Set the pair contact distance thresholds for which collision should be considered on a per pair basis. More...
 
void setCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose) override final
 Set a single static collision object's tansforms. More...
 
void setCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2) override final
 Set a single cast(moving) collision object's tansforms. More...
 
void setCollisionObjectsTransform (const std::vector< std::string > &names, const tesseract_common::VectorIsometry3d &pose1, const tesseract_common::VectorIsometry3d &pose2) override final
 Set a series of cast(moving) collision object's tranforms. More...
 
void setCollisionObjectsTransform (const std::vector< std::string > &names, const tesseract_common::VectorIsometry3d &poses) override final
 Set a series of static collision object's tranforms. More...
 
void setCollisionObjectsTransform (const tesseract_common::TransformMap &pose1, const tesseract_common::TransformMap &pose2) override final
 Set a series of cast(moving) collision object's tranforms. More...
 
void setCollisionObjectsTransform (const tesseract_common::TransformMap &transforms) override final
 Set a series of static collision object's tranforms. More...
 
void setContactAllowedValidator (std::shared_ptr< const tesseract_common::ContactAllowedValidator > validator) override final
 Set the active function for determining if two links are allowed to be in collision. More...
 
void setDefaultCollisionMargin (double default_collision_margin) override final
 Set the default collision margin. More...
 
 ~BulletCastSimpleManager () override=default
 
- Public Member Functions inherited from tesseract_collision::ContinuousContactManager
virtual void applyContactManagerConfig (const ContactManagerConfig &config)
 Applies settings in the config. More...
 
 ContinuousContactManager ()=default
 
 ContinuousContactManager (const ContinuousContactManager &)=delete
 
 ContinuousContactManager (ContinuousContactManager &&)=delete
 
ContinuousContactManageroperator= (const ContinuousContactManager &)=delete
 
ContinuousContactManageroperator= (ContinuousContactManager &&)=delete
 
virtual ~ContinuousContactManager ()=default
 

Private Member Functions

void onCollisionMarginDataChanged ()
 This function will update internal data when margin data has changed. More...
 

Private Attributes

std::vector< std::string > active_
 A list of the active collision objects. More...
 
TesseractCollisionConfiguration coll_config_
 The bullet collision configuration. More...
 
std::vector< std::string > collision_objects_
 A list of the collision objects. More...
 
TesseractCollisionConfigurationInfo config_info_
 The bullet collision configuration information. More...
 
ContactTestData contact_test_data_
 This is used when contactTest is called. It is also added as a user point to the collsion objects so it can be used to exit collision checking for compound shapes. More...
 
std::vector< COW::Ptrcows_
 A vector of collision objects (active followed by static) More...
 
btDispatcherInfo dispatch_info_
 The bullet collision dispatcher configuration information. More...
 
std::unique_ptr< btCollisionDispatcher > dispatcher_
 The bullet collision dispatcher used for getting object to object collison algorithm. More...
 
Link2Cow link2castcow_
 A map of cast collision objects being managed. More...
 
Link2Cow link2cow_
 A map of collision objects being managed. More...
 
std::string name_
 

Detailed Description

A simple implementation of a tesseract manager which does not use BHV.

Definition at line 51 of file bullet_cast_simple_manager.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 55 of file bullet_cast_simple_manager.h.

◆ ConstUPtr

Definition at line 57 of file bullet_cast_simple_manager.h.

◆ Ptr

Definition at line 54 of file bullet_cast_simple_manager.h.

◆ UPtr

Definition at line 56 of file bullet_cast_simple_manager.h.

Constructor & Destructor Documentation

◆ BulletCastSimpleManager() [1/3]

tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::BulletCastSimpleManager ( std::string  name = "BulletCastSimpleManager",
TesseractCollisionConfigurationInfo  config_info = TesseractCollisionConfigurationInfo() 
)

Definition at line 50 of file bullet_cast_simple_manager.cpp.

◆ ~BulletCastSimpleManager()

tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::~BulletCastSimpleManager ( )
overridedefault

◆ BulletCastSimpleManager() [2/3]

tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::BulletCastSimpleManager ( const BulletCastSimpleManager )
delete

◆ BulletCastSimpleManager() [3/3]

tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::BulletCastSimpleManager ( BulletCastSimpleManager &&  )
delete

Member Function Documentation

◆ addCollisionObject() [1/2]

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::addCollisionObject ( const COW::Ptr cow)

A a bullet collision object to the manager.

Parameters
cowThe tesseract bullet collision object

Definition at line 459 of file bullet_cast_simple_manager.cpp.

◆ addCollisionObject() [2/2]

bool tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::addCollisionObject ( const std::string &  name,
const int &  mask_id,
const CollisionShapesConst shapes,
const tesseract_common::VectorIsometry3d shape_poses,
bool  enabled = true 
)
finaloverridevirtual

Add a collision object to the checker.

All objects are added should initially be added as static objects. Use the setContactRequest method of defining which collision objects are moving.

Parameters
nameThe name of the object, must be unique.
mask_idUser defined id which gets stored in the results structure.
shapesA vector of shapes that make up the collision object.
shape_posesA vector of poses for each shape, must be same length as shapes
shape_typesA vector of shape types for encode the collision object. If the vector is of length 1 it is used for all shapes.
collision_object_typesA int identifying a conversion mode for the object. (ex. convert meshes to convex_hulls)
enabledIndicate if the object is enabled for collision checking.
Returns
true if successfully added, otherwise false.

Implements tesseract_collision::ContinuousContactManager.

Definition at line 93 of file bullet_cast_simple_manager.cpp.

◆ clone()

ContinuousContactManager::UPtr tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::clone ( ) const
finaloverridevirtual

Clone the manager.

This is to be used for multi threaded application. A user should make a clone for each thread.

Implements tesseract_collision::ContinuousContactManager.

Definition at line 67 of file bullet_cast_simple_manager.cpp.

◆ contactTest()

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::contactTest ( ContactResultMap collisions,
const ContactRequest request 
)
finaloverridevirtual

Perform a contact test for all objects based.

Parameters
collisionsThe Contact results data
typeThe type of contact test

Implements tesseract_collision::ContinuousContactManager.

Definition at line 391 of file bullet_cast_simple_manager.cpp.

◆ disableCollisionObject()

bool tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::disableCollisionObject ( const std::string &  name)
finaloverridevirtual

Disable an object.

Parameters
nameThe name of the object

Implements tesseract_collision::ContinuousContactManager.

Definition at line 162 of file bullet_cast_simple_manager.cpp.

◆ enableCollisionObject()

bool tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::enableCollisionObject ( const std::string &  name)
finaloverridevirtual

Enable an object.

Parameters
nameThe name of the object

Implements tesseract_collision::ContinuousContactManager.

Definition at line 149 of file bullet_cast_simple_manager.cpp.

◆ getActiveCollisionObjects()

const std::vector< std::string > & tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getActiveCollisionObjects ( ) const
finaloverridevirtual

Get which collision objects can move.

Returns
A list of collision object names

Implements tesseract_collision::ContinuousContactManager.

Definition at line 341 of file bullet_cast_simple_manager.cpp.

◆ getCollisionMarginData()

const CollisionMarginData & tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getCollisionMarginData ( ) const
finaloverridevirtual

Get the contact distance threshold.

Returns
The contact distance

Implements tesseract_collision::ContinuousContactManager.

Definition at line 349 of file bullet_cast_simple_manager.cpp.

◆ getCollisionObjectGeometries()

const CollisionShapesConst & tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getCollisionObjectGeometries ( const std::string &  name) const
finaloverridevirtual

Get a collision objects collision geometries.

Parameters
nameThe collision objects name
Returns
A vector of collision geometries. The vector will be empty if the collision object is not found.

Implements tesseract_collision::ContinuousContactManager.

Definition at line 114 of file bullet_cast_simple_manager.cpp.

◆ getCollisionObjectGeometriesTransforms()

const tesseract_common::VectorIsometry3d & tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getCollisionObjectGeometriesTransforms ( const std::string &  name) const
finaloverridevirtual

Get a collision objects collision geometries transforms.

Parameters
nameThe collision objects name
Returns
A vector of collision geometries transforms. The vector will be empty if the collision object is not found.

Implements tesseract_collision::ContinuousContactManager.

Definition at line 122 of file bullet_cast_simple_manager.cpp.

◆ getCollisionObjects()

const std::vector< std::string > & tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getCollisionObjects ( ) const
finaloverridevirtual

Get all collision objects.

Returns
A list of collision object names

Implements tesseract_collision::ContinuousContactManager.

Definition at line 305 of file bullet_cast_simple_manager.cpp.

◆ getContactAllowedValidator()

std::shared_ptr< const tesseract_common::ContactAllowedValidator > tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getContactAllowedValidator ( ) const
finaloverridevirtual

Get the active function for determining if two links are allowed to be in collision.

Implements tesseract_collision::ContinuousContactManager.

Definition at line 387 of file bullet_cast_simple_manager.cpp.

◆ getName()

std::string tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::getName ( ) const
finaloverridevirtual

Get the name of the contact manager.

Returns
The name

Implements tesseract_collision::ContinuousContactManager.

Definition at line 65 of file bullet_cast_simple_manager.cpp.

◆ hasCollisionObject()

bool tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::hasCollisionObject ( const std::string &  name) const
finaloverridevirtual

Find if a collision object already exists.

Parameters
nameThe name of the collision object
Returns
true if it exists, otherwise false.

Implements tesseract_collision::ContinuousContactManager.

Definition at line 129 of file bullet_cast_simple_manager.cpp.

◆ incrementCollisionMargin()

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::incrementCollisionMargin ( double  increment)
finaloverridevirtual

Increment the collision margin data by some value.

Parameters
incrementThe value to increment the collision margin value

Implements tesseract_collision::ContinuousContactManager.

Definition at line 375 of file bullet_cast_simple_manager.cpp.

◆ isCollisionObjectEnabled()

bool tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::isCollisionObjectEnabled ( const std::string &  name) const
finaloverridevirtual

Check if collision object is enabled.

Parameters
nameThe name of the object
Returns
True if enabled, otherwise false

Implements tesseract_collision::ContinuousContactManager.

Definition at line 175 of file bullet_cast_simple_manager.cpp.

◆ onCollisionMarginDataChanged()

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::onCollisionMarginDataChanged ( )
private

This function will update internal data when margin data has changed.

Definition at line 478 of file bullet_cast_simple_manager.cpp.

◆ operator=() [1/2]

BulletCastSimpleManager& tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::operator= ( BulletCastSimpleManager &&  )
delete

◆ operator=() [2/2]

BulletCastSimpleManager& tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::operator= ( const BulletCastSimpleManager )
delete

◆ removeCollisionObject()

bool tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::removeCollisionObject ( const std::string &  name)
finaloverridevirtual

Remove an object from the checker.

Parameters
nameThe name of the object
Returns
true if successfully removed, otherwise false.

Implements tesseract_collision::ContinuousContactManager.

Definition at line 134 of file bullet_cast_simple_manager.cpp.

◆ setActiveCollisionObjects()

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setActiveCollisionObjects ( const std::vector< std::string > &  names)
finaloverridevirtual

Set which collision objects can move.

Parameters
namesA vector of collision object names

Implements tesseract_collision::ContinuousContactManager.

Definition at line 307 of file bullet_cast_simple_manager.cpp.

◆ setCollisionMarginData()

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setCollisionMarginData ( CollisionMarginData  collision_margin_data)
finaloverridevirtual

Set the contact distance threshold.

Parameters
collision_margin_dataThe contact distance

Implements tesseract_collision::ContinuousContactManager.

Definition at line 343 of file bullet_cast_simple_manager.cpp.

◆ setCollisionMarginPair()

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setCollisionMarginPair ( const std::string &  name1,
const std::string &  name2,
double  collision_margin 
)
finaloverridevirtual

Set the margin for a given contact pair.

The order of the object names does not matter, that is handled internal to the class.

Parameters
obj1The first object name. Order doesn't matter
obj2The Second object name. Order doesn't matter
collision_margincontacts with distance < collision_margin are considered in collision

Implements tesseract_collision::ContinuousContactManager.

Definition at line 367 of file bullet_cast_simple_manager.cpp.

◆ setCollisionMarginPairData()

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setCollisionMarginPairData ( const CollisionMarginPairData pair_margin_data,
CollisionMarginPairOverrideType  override_type = CollisionMarginPairOverrideType::REPLACE 
)
finaloverridevirtual

Set the pair contact distance thresholds for which collision should be considered on a per pair basis.

Parameters
pair_margin_dataContains the pair collision margins that will replace the current settings
override_typeThis determines how the provided CollisionMarginData is applied

Implements tesseract_collision::ContinuousContactManager.

Definition at line 354 of file bullet_cast_simple_manager.cpp.

◆ setCollisionObjectsTransform() [1/6]

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setCollisionObjectsTransform ( const std::string &  name,
const Eigen::Isometry3d &  pose 
)
finaloverridevirtual

Set a single static collision object's tansforms.

Parameters
nameThe name of the object
poseThe tranformation in world

Implements tesseract_collision::ContinuousContactManager.

Definition at line 184 of file bullet_cast_simple_manager.cpp.

◆ setCollisionObjectsTransform() [2/6]

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setCollisionObjectsTransform ( const std::string &  name,
const Eigen::Isometry3d &  pose1,
const Eigen::Isometry3d &  pose2 
)
finaloverridevirtual

Set a single cast(moving) collision object's tansforms.

This should only be used for moving objects. Use the base class methods for static objects.

Parameters
nameThe name of the object
pose1The start tranformation in world
pose2The end tranformation in world

Implements tesseract_collision::ContinuousContactManager.

Definition at line 211 of file bullet_cast_simple_manager.cpp.

◆ setCollisionObjectsTransform() [3/6]

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setCollisionObjectsTransform ( const std::vector< std::string > &  names,
const tesseract_common::VectorIsometry3d pose1,
const tesseract_common::VectorIsometry3d pose2 
)
finaloverridevirtual

Set a series of cast(moving) collision object's tranforms.

This should only be used for moving objects. Use the base class methods for static objects.

Parameters
namesThe name of the object
pose1The start tranformations in world
pose2The end tranformations in world

Implements tesseract_collision::ContinuousContactManager.

Definition at line 280 of file bullet_cast_simple_manager.cpp.

◆ setCollisionObjectsTransform() [4/6]

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setCollisionObjectsTransform ( const std::vector< std::string > &  names,
const tesseract_common::VectorIsometry3d poses 
)
finaloverridevirtual

Set a series of static collision object's tranforms.

Parameters
namesThe name of the object
posesThe tranformation in world

Implements tesseract_collision::ContinuousContactManager.

Definition at line 197 of file bullet_cast_simple_manager.cpp.

◆ setCollisionObjectsTransform() [5/6]

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setCollisionObjectsTransform ( const tesseract_common::TransformMap pose1,
const tesseract_common::TransformMap pose2 
)
finaloverridevirtual

Set a series of cast(moving) collision object's tranforms.

This should only be used for moving objects. Use the base class methods for static objects.

Parameters
pose1A start transform map <name, pose>
pose2A end transform map <name, pose>

Implements tesseract_collision::ContinuousContactManager.

Definition at line 290 of file bullet_cast_simple_manager.cpp.

◆ setCollisionObjectsTransform() [6/6]

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setCollisionObjectsTransform ( const tesseract_common::TransformMap transforms)
finaloverridevirtual

Set a series of static collision object's tranforms.

Parameters
transformsA transform map <name, pose>

Implements tesseract_collision::ContinuousContactManager.

Definition at line 205 of file bullet_cast_simple_manager.cpp.

◆ setContactAllowedValidator()

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setContactAllowedValidator ( std::shared_ptr< const tesseract_common::ContactAllowedValidator validator)
finaloverridevirtual

Set the active function for determining if two links are allowed to be in collision.

Implements tesseract_collision::ContinuousContactManager.

Definition at line 381 of file bullet_cast_simple_manager.cpp.

◆ setDefaultCollisionMargin()

void tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::setDefaultCollisionMargin ( double  default_collision_margin)
finaloverridevirtual

Set the default collision margin.

Parameters
default_collision_marginNew default collision margin

Implements tesseract_collision::ContinuousContactManager.

Definition at line 361 of file bullet_cast_simple_manager.cpp.

Member Data Documentation

◆ active_

std::vector<std::string> tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::active_
private

A list of the active collision objects.

Definition at line 148 of file bullet_cast_simple_manager.h.

◆ coll_config_

TesseractCollisionConfiguration tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::coll_config_
private

The bullet collision configuration.

Definition at line 158 of file bullet_cast_simple_manager.h.

◆ collision_objects_

std::vector<std::string> tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::collision_objects_
private

A list of the collision objects.

Definition at line 150 of file bullet_cast_simple_manager.h.

◆ config_info_

TesseractCollisionConfigurationInfo tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::config_info_
private

The bullet collision configuration information.

Definition at line 156 of file bullet_cast_simple_manager.h.

◆ contact_test_data_

ContactTestData tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::contact_test_data_
private

This is used when contactTest is called. It is also added as a user point to the collsion objects so it can be used to exit collision checking for compound shapes.

Definition at line 170 of file bullet_cast_simple_manager.h.

◆ cows_

std::vector<COW::Ptr> tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::cows_
private

A vector of collision objects (active followed by static)

Definition at line 162 of file bullet_cast_simple_manager.h.

◆ dispatch_info_

btDispatcherInfo tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::dispatch_info_
private

The bullet collision dispatcher configuration information.

Definition at line 154 of file bullet_cast_simple_manager.h.

◆ dispatcher_

std::unique_ptr<btCollisionDispatcher> tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::dispatcher_
private

The bullet collision dispatcher used for getting object to object collison algorithm.

Definition at line 152 of file bullet_cast_simple_manager.h.

◆ link2castcow_

Link2Cow tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::link2castcow_
private

A map of cast collision objects being managed.

Definition at line 164 of file bullet_cast_simple_manager.h.

◆ link2cow_

Link2Cow tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::link2cow_
private

A map of collision objects being managed.

Definition at line 160 of file bullet_cast_simple_manager.h.

◆ name_

std::string tesseract_collision::tesseract_collision_bullet::BulletCastSimpleManager::name_
private

Definition at line 146 of file bullet_cast_simple_manager.h.


The documentation for this class was generated from the following files:


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