Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager Class Reference

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

#include <bullet_discrete_simple_manager.h>

Inheritance diagram for tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager:
Inheritance graph
[legend]
Collaboration diagram for tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager:
Collaboration graph
[legend]

Public Types

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

Public Member Functions

 BulletDiscreteSimpleManager (std::string name="BulletDiscreteSimpleManager", TesseractCollisionConfigurationInfo config_info=TesseractCollisionConfigurationInfo())
 
 ~BulletDiscreteSimpleManager () override=default
 
 BulletDiscreteSimpleManager (const BulletDiscreteSimpleManager &)=delete
 
BulletDiscreteSimpleManageroperator= (const BulletDiscreteSimpleManager &)=delete
 
 BulletDiscreteSimpleManager (BulletDiscreteSimpleManager &&)=delete
 
BulletDiscreteSimpleManageroperator= (BulletDiscreteSimpleManager &&)=delete
 
std::string getName () const override final
 Get the name of the contact manager. More...
 
DiscreteContactManager::UPtr clone () const override final
 Clone 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 object to the checker. 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...
 
bool hasCollisionObject (const std::string &name) const override final
 Find if a collision object already exists. More...
 
bool removeCollisionObject (const std::string &name) override final
 Remove an object from the checker. More...
 
bool enableCollisionObject (const std::string &name) override final
 Enable an object. More...
 
bool disableCollisionObject (const std::string &name) override final
 Disable an object. More...
 
bool isCollisionObjectEnabled (const std::string &name) const override final
 Check if collision object is enabled. More...
 
void setCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose) override final
 Set a single collision object's transforms. More...
 
void setCollisionObjectsTransform (const std::vector< std::string > &names, const tesseract_common::VectorIsometry3d &poses) override final
 Set a series of collision object's transforms. More...
 
void setCollisionObjectsTransform (const tesseract_common::TransformMap &transforms) override final
 Set a series of collision object's transforms. More...
 
const std::vector< std::string > & getCollisionObjects () const override final
 Get all collision objects. More...
 
void setActiveCollisionObjects (const std::vector< std::string > &names) override final
 Set which collision objects can move. More...
 
const std::vector< std::string > & getActiveCollisionObjects () const override final
 Get which collision objects can move. More...
 
void setCollisionMarginData (CollisionMarginData collision_margin_data, CollisionMarginOverrideType override_type=CollisionMarginOverrideType::REPLACE) override final
 Set the contact distance thresholds for which collision should be considered on a per pair basis. More...
 
void setDefaultCollisionMarginData (double default_collision_margin) override final
 Set the default collision margin. More...
 
void setPairCollisionMarginData (const std::string &name1, const std::string &name2, double collision_margin) override final
 Set the margin for a given contact pair. More...
 
const CollisionMarginDatagetCollisionMarginData () const override final
 Get the contact distance threshold. More...
 
void setIsContactAllowedFn (IsContactAllowedFn fn) override final
 Set the active function for determining if two links are allowed to be in collision. More...
 
IsContactAllowedFn getIsContactAllowedFn () const override final
 Get the active function for determining if two links are allowed to be in collision. More...
 
void contactTest (ContactResultMap &collisions, const ContactRequest &request) override final
 Perform a contact test for all objects based. More...
 
void addCollisionObject (const COW::Ptr &cow)
 A a bullet collision object to the manager. More...
 
- Public Member Functions inherited from tesseract_collision::DiscreteContactManager
 DiscreteContactManager ()=default
 
virtual ~DiscreteContactManager ()=default
 
 DiscreteContactManager (const DiscreteContactManager &)=delete
 
DiscreteContactManageroperator= (const DiscreteContactManager &)=delete
 
 DiscreteContactManager (DiscreteContactManager &&)=delete
 
DiscreteContactManageroperator= (DiscreteContactManager &&)=delete
 
virtual std::string getName () const =0
 Get the name of the contact manager. More...
 
virtual DiscreteContactManager::UPtr clone () const =0
 Clone the manager. More...
 
virtual bool addCollisionObject (const std::string &name, const int &mask_id, const CollisionShapesConst &shapes, const tesseract_common::VectorIsometry3d &shape_poses, bool enabled=true)=0
 Add a object to the checker. More...
 
virtual const CollisionShapesConstgetCollisionObjectGeometries (const std::string &name) const =0
 Get a collision objects collision geometries. More...
 
virtual const tesseract_common::VectorIsometry3dgetCollisionObjectGeometriesTransforms (const std::string &name) const =0
 Get a collision objects collision geometries transforms. More...
 
virtual bool hasCollisionObject (const std::string &name) const =0
 Find if a collision object already exists. More...
 
virtual bool removeCollisionObject (const std::string &name)=0
 Remove an object from the checker. More...
 
virtual bool enableCollisionObject (const std::string &name)=0
 Enable an object. More...
 
virtual bool disableCollisionObject (const std::string &name)=0
 Disable an object. More...
 
virtual bool isCollisionObjectEnabled (const std::string &name) const =0
 Check if collision object is enabled. More...
 
virtual void setCollisionObjectsTransform (const std::string &name, const Eigen::Isometry3d &pose)=0
 Set a single collision object's transforms. More...
 
virtual void setCollisionObjectsTransform (const std::vector< std::string > &names, const tesseract_common::VectorIsometry3d &poses)=0
 Set a series of collision object's transforms. More...
 
virtual void setCollisionObjectsTransform (const tesseract_common::TransformMap &transforms)=0
 Set a series of collision object's transforms. More...
 
virtual const std::vector< std::string > & getCollisionObjects () const =0
 Get all collision objects. More...
 
virtual void setActiveCollisionObjects (const std::vector< std::string > &names)=0
 Set which collision objects can move. More...
 
virtual const std::vector< std::string > & getActiveCollisionObjects () const =0
 Get which collision objects can move. More...
 
virtual void setCollisionMarginData (CollisionMarginData collision_margin_data, CollisionMarginOverrideType override_type=CollisionMarginOverrideType::REPLACE)=0
 Set the contact distance thresholds for which collision should be considered on a per pair basis. More...
 
virtual void setDefaultCollisionMarginData (double default_collision_margin)=0
 Set the default collision margin. More...
 
virtual void setPairCollisionMarginData (const std::string &name1, const std::string &name2, double collision_margin)=0
 Set the margin for a given contact pair. More...
 
virtual const CollisionMarginDatagetCollisionMarginData () const =0
 Get the contact distance threshold. More...
 
virtual void setIsContactAllowedFn (IsContactAllowedFn fn)=0
 Set the active function for determining if two links are allowed to be in collision. More...
 
virtual IsContactAllowedFn getIsContactAllowedFn () const =0
 Get the active function for determining if two links are allowed to be in collision. More...
 
virtual void contactTest (ContactResultMap &collisions, const ContactRequest &request)=0
 Perform a contact test for all objects based. More...
 
virtual void applyContactManagerConfig (const ContactManagerConfig &config)
 Applies settings in the config. More...
 

Private Member Functions

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

Private Attributes

std::string name_
 
std::vector< std::string > active_
 A list of the active collision objects. More...
 
std::vector< std::string > collision_objects_
 A list of the collision objects. More...
 
std::unique_ptr< btCollisionDispatcher > dispatcher_
 The bullet collision dispatcher used for getting object to object collison algorithm. More...
 
btDispatcherInfo dispatch_info_
 The bullet collision dispatcher configuration information. More...
 
TesseractCollisionConfigurationInfo config_info_
 The bullet collision configuration information. More...
 
TesseractCollisionConfiguration coll_config_
 The bullet collision configuration. More...
 
Link2Cow link2cow_
 A map of all (static and active) collision objects being managed. More...
 
std::vector< COW::Ptrcows_
 A vector of collision objects (active followed by static) 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...
 

Detailed Description

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

Member Typedef Documentation

◆ ConstPtr

◆ ConstUPtr

◆ Ptr

◆ UPtr

Constructor & Destructor Documentation

◆ BulletDiscreteSimpleManager() [1/3]

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

◆ ~BulletDiscreteSimpleManager()

tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::~BulletDiscreteSimpleManager ( )
overridedefault

◆ BulletDiscreteSimpleManager() [2/3]

tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::BulletDiscreteSimpleManager ( const BulletDiscreteSimpleManager )
delete

◆ BulletDiscreteSimpleManager() [3/3]

tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::BulletDiscreteSimpleManager ( BulletDiscreteSimpleManager &&  )
delete

Member Function Documentation

◆ addCollisionObject() [1/2]

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

A a bullet collision object to the manager.

Parameters
cowThe tesseract bullet collision object

◆ addCollisionObject() [2/2]

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

Add a object to the checker.

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
Returns
true if successfully added, otherwise false.

Implements tesseract_collision::DiscreteContactManager.

◆ clone()

DiscreteContactManager::UPtr tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::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::DiscreteContactManager.

◆ contactTest()

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

Perform a contact test for all objects based.

Parameters
collisionsThe contact results data
requestThe contact request data

Implements tesseract_collision::DiscreteContactManager.

◆ disableCollisionObject()

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

Disable an object.

Parameters
nameThe name of the object

Implements tesseract_collision::DiscreteContactManager.

◆ enableCollisionObject()

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

Enable an object.

Parameters
nameThe name of the object

Implements tesseract_collision::DiscreteContactManager.

◆ getActiveCollisionObjects()

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

Get which collision objects can move.

Returns
A list of collision object names

Implements tesseract_collision::DiscreteContactManager.

◆ getCollisionMarginData()

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

Get the contact distance threshold.

Returns
The contact distance

Implements tesseract_collision::DiscreteContactManager.

◆ getCollisionObjectGeometries()

const CollisionShapesConst & tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::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::DiscreteContactManager.

◆ getCollisionObjectGeometriesTransforms()

const tesseract_common::VectorIsometry3d & tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::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::DiscreteContactManager.

◆ getCollisionObjects()

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

Get all collision objects.

Returns
A list of collision object names

Implements tesseract_collision::DiscreteContactManager.

◆ getIsContactAllowedFn()

IsContactAllowedFn tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::getIsContactAllowedFn ( ) const
finaloverridevirtual

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

Implements tesseract_collision::DiscreteContactManager.

◆ getName()

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

Get the name of the contact manager.

Returns
The name

Implements tesseract_collision::DiscreteContactManager.

◆ hasCollisionObject()

bool tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::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::DiscreteContactManager.

◆ isCollisionObjectEnabled()

bool tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::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::DiscreteContactManager.

◆ onCollisionMarginDataChanged()

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

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

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ removeCollisionObject()

bool tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::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::DiscreteContactManager.

◆ setActiveCollisionObjects()

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

Set which collision objects can move.

Parameters
namesA vector of collision object names

Implements tesseract_collision::DiscreteContactManager.

◆ setCollisionMarginData()

void tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::setCollisionMarginData ( CollisionMarginData  collision_margin_data,
CollisionMarginOverrideType  override_type = CollisionMarginOverrideType::REPLACE 
)
finaloverridevirtual

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

Parameters
collision_margin_dataContains the data that will replace the current settings
override_typeThis determines how the provided CollisionMarginData is applied

Implements tesseract_collision::DiscreteContactManager.

◆ setCollisionObjectsTransform() [1/3]

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

Set a single collision object's transforms.

Parameters
nameThe name of the object
poseThe transformation in world

Implements tesseract_collision::DiscreteContactManager.

◆ setCollisionObjectsTransform() [2/3]

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

Set a series of collision object's transforms.

Parameters
namesThe name of the object
posesThe transformation in world

Implements tesseract_collision::DiscreteContactManager.

◆ setCollisionObjectsTransform() [3/3]

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

Set a series of collision object's transforms.

Parameters
transformsA transform map <name, pose>

Implements tesseract_collision::DiscreteContactManager.

◆ setDefaultCollisionMarginData()

void tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::setDefaultCollisionMarginData ( double  default_collision_margin)
finaloverridevirtual

Set the default collision margin.

Parameters
default_collision_marginNew default collision margin

Implements tesseract_collision::DiscreteContactManager.

◆ setIsContactAllowedFn()

void tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::setIsContactAllowedFn ( IsContactAllowedFn  fn)
finaloverridevirtual

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

Implements tesseract_collision::DiscreteContactManager.

◆ setPairCollisionMarginData()

void tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::setPairCollisionMarginData ( 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::DiscreteContactManager.

Member Data Documentation

◆ active_

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

A list of the active collision objects.

◆ coll_config_

TesseractCollisionConfiguration tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::coll_config_
private

The bullet collision configuration.

◆ collision_objects_

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

A list of the collision objects.

◆ config_info_

TesseractCollisionConfigurationInfo tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::config_info_
private

The bullet collision configuration information.

◆ contact_test_data_

ContactTestData tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::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.

◆ cows_

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

A vector of collision objects (active followed by static)

◆ dispatch_info_

btDispatcherInfo tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::dispatch_info_
private

The bullet collision dispatcher configuration information.

◆ dispatcher_

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

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

◆ link2cow_

Link2Cow tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::link2cow_
private

A map of all (static and active) collision objects being managed.

◆ name_

std::string tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::name_
private

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