DART  6.7.3
dart::collision::BulletCollisionDetector Class Reference

#include <BulletCollisionDetector.hpp>

Inheritance diagram for dart::collision::BulletCollisionDetector:
dart::collision::CollisionDetector

Classes

class  BulletCollisionShapeDeleter
 This deleter is responsible for deleting BulletCollsionShape objects and removing them from mShapeMap when they are not shared by any CollisionObjects. More...
 
struct  ShapeInfo
 Information for a shape that was generated by this collision detector. More...
 

Public Types

using Factory = common::Factory< std::string, CollisionDetector, std::shared_ptr< CollisionDetector > >
 
using SingletonFactory = common::Singleton< Factory >
 
template<typename Derived >
using Registrar = common::FactoryRegistrar< std::string, CollisionDetector, Derived, std::shared_ptr< CollisionDetector > >
 

Public Member Functions

virtual ~BulletCollisionDetector ()
 Constructor. More...
 
std::shared_ptr< CollisionDetectorcloneWithoutCollisionObjects () override
 Create a clone of this CollisionDetector. More...
 
const std::string & getType () const override
 Return collision detection engine type as a std::string. More...
 
std::unique_ptr< CollisionGroupcreateCollisionGroup () override
 Create a collision group. More...
 
bool collide (CollisionGroup *group, const CollisionOption &option=CollisionOption(false, 1u, nullptr), CollisionResult *result=nullptr) override
 Perform collision check for a single group. More...
 
bool collide (CollisionGroup *group1, CollisionGroup *group2, const CollisionOption &option=CollisionOption(false, 1u, nullptr), CollisionResult *result=nullptr) override
 Perform collision check for two groups. More...
 
double distance (CollisionGroup *group, const DistanceOption &option=DistanceOption(false, 0.0, nullptr), DistanceResult *result=nullptr) override
 Get the minimum signed distance between the Shape pairs in the given CollisionGroup. More...
 
double distance (CollisionGroup *group1, CollisionGroup *group2, const DistanceOption &option=DistanceOption(false, 0.0, nullptr), DistanceResult *result=nullptr) override
 Get the minimum signed distance between the Shape pairs where a pair consist of two shapes from each groups (one from group1 and one from group2). More...
 
virtual std::unique_ptr< CollisionGroupcreateCollisionGroup ()=0
 Create a collision group. More...
 
template<typename... Args>
std::unique_ptr< CollisionGroupcreateCollisionGroup (const Args &... args)
 Create a collision group from any objects that are supported by CollisionGroup::addShapeFramesOf(). More...
 
template<typename... Args>
std::unique_ptr< CollisionGroupcreateCollisionGroup (const Args &... args)
 Create a collision group from any objects that are supported by CollisionGroup::addShapeFramesOf(). More...
 
std::shared_ptr< CollisionGroupcreateCollisionGroupAsSharedPtr ()
 Helper function that creates and returns CollisionGroup as a shared_ptr. More...
 
template<typename... Args>
std::shared_ptr< CollisionGroupcreateCollisionGroupAsSharedPtr (const Args &... args)
 Helper function that creates and returns CollisionGroup as shared_ptr. More...
 

Static Public Member Functions

static std::shared_ptr< BulletCollisionDetectorcreate ()
 
static const std::string & getStaticType ()
 Get collision detector type for this class. More...
 
static FactorygetFactory ()
 Returns the singleton factory. More...
 

Protected Member Functions

 BulletCollisionDetector ()
 Constructor. More...
 
std::unique_ptr< CollisionObjectcreateCollisionObject (const dynamics::ShapeFrame *shapeFrame) override
 Create CollisionObject. More...
 
void refreshCollisionObject (CollisionObject *object) override
 Update the collision geometry of a ShapeFrame. More...
 
void notifyCollisionObjectDestroying (CollisionObject *object) override
 Notify that a CollisionObject is destroying. Do nothing by default. More...
 
std::shared_ptr< CollisionObjectclaimCollisionObject (const dynamics::ShapeFrame *shapeFrame)
 Claim CollisionObject associated with shapeFrame. More...
 

Protected Attributes

std::unique_ptr< CollisionObjectManagermCollisionObjectManager
 

Private Member Functions

std::shared_ptr< BulletCollisionShapeclaimBulletCollisionShape (const dynamics::ConstShapePtr &shape)
 
void reclaimBulletCollisionShape (const dynamics::ConstShapePtr &shape)
 
std::unique_ptr< BulletCollisionShapecreateBulletCollisionShape (const dynamics::ConstShapePtr &shape)
 

Private Attributes

std::map< dynamics::ConstShapePtr, ShapeInfomShapeMap
 
std::unique_ptr< BulletCollisionGroupmGroupForFiltering
 

Static Private Attributes

static Registrar< BulletCollisionDetectormRegistrar
 

Friends

class CollisionDetector
 

Member Typedef Documentation

◆ Factory

◆ Registrar

template<typename Derived >
using dart::collision::CollisionDetector::Registrar = common::FactoryRegistrar< std::string, CollisionDetector, Derived, std::shared_ptr<CollisionDetector> >
inherited

◆ SingletonFactory

Constructor & Destructor Documentation

◆ ~BulletCollisionDetector()

dart::collision::BulletCollisionDetector::~BulletCollisionDetector ( )
virtual

Constructor.

◆ BulletCollisionDetector()

dart::collision::BulletCollisionDetector::BulletCollisionDetector ( )
protected

Constructor.

Member Function Documentation

◆ claimBulletCollisionShape()

std::shared_ptr< BulletCollisionShape > dart::collision::BulletCollisionDetector::claimBulletCollisionShape ( const dynamics::ConstShapePtr shape)
private

◆ claimCollisionObject()

std::shared_ptr< CollisionObject > dart::collision::CollisionDetector::claimCollisionObject ( const dynamics::ShapeFrame shapeFrame)
protectedinherited

Claim CollisionObject associated with shapeFrame.

New CollisionObject will be created if it hasn't created yet for shapeFrame.

◆ cloneWithoutCollisionObjects()

std::shared_ptr< CollisionDetector > dart::collision::BulletCollisionDetector::cloneWithoutCollisionObjects ( )
overridevirtual

Create a clone of this CollisionDetector.

All the properties will be copied over, but not collision objects.

Implements dart::collision::CollisionDetector.

◆ collide() [1/2]

bool dart::collision::BulletCollisionDetector::collide ( CollisionGroup group,
const CollisionOption option = CollisionOption(false, 1u, nullptr),
CollisionResult result = nullptr 
)
overridevirtual

Perform collision check for a single group.

If nullptr is passed to result, then the this returns only simple information whether there is a collision of not.

Implements dart::collision::CollisionDetector.

◆ collide() [2/2]

bool dart::collision::BulletCollisionDetector::collide ( CollisionGroup group1,
CollisionGroup group2,
const CollisionOption option = CollisionOption(false, 1u, nullptr),
CollisionResult result = nullptr 
)
overridevirtual

Perform collision check for two groups.

If nullptr is passed to result, then the this returns only simple information whether there is a collision of not.

Implements dart::collision::CollisionDetector.

◆ create()

std::shared_ptr< BulletCollisionDetector > dart::collision::BulletCollisionDetector::create ( )
static

◆ createBulletCollisionShape()

std::unique_ptr< BulletCollisionShape > dart::collision::BulletCollisionDetector::createBulletCollisionShape ( const dynamics::ConstShapePtr shape)
private

◆ createCollisionGroup() [1/4]

std::unique_ptr< CollisionGroup > dart::collision::BulletCollisionDetector::createCollisionGroup ( )
overridevirtual

Create a collision group.

Implements dart::collision::CollisionDetector.

◆ createCollisionGroup() [2/4]

virtual std::unique_ptr<CollisionGroup> dart::collision::CollisionDetector::createCollisionGroup
virtual

Create a collision group.

Implements dart::collision::CollisionDetector.

◆ createCollisionGroup() [3/4]

template<typename... Args>
std::unique_ptr< CollisionGroup > dart::collision::CollisionDetector::createCollisionGroup ( typename...  Args)

Create a collision group from any objects that are supported by CollisionGroup::addShapeFramesOf().

The objects can be any of ShapeFrame, std::vector<ShapeFrame>, CollisionGroup, BodyNode, and Skeleton.

Note that this function adds only the ShapeFrames of each object at the moment that this function is called. Any later addition to or removal of the ShapeFrames that are attached to these objects will NOT be noticed.

◆ createCollisionGroup() [4/4]

template<typename... Args>
std::unique_ptr< CollisionGroup > dart::collision::CollisionDetector::createCollisionGroup ( const Args &...  args)
inherited

Create a collision group from any objects that are supported by CollisionGroup::addShapeFramesOf().

The objects can be any of ShapeFrame, std::vector<ShapeFrame>, CollisionGroup, BodyNode, and Skeleton.

Note that this function adds only the ShapeFrames of each object at the moment that this function is called. Any later addition to or removal of the ShapeFrames that are attached to these objects will NOT be noticed.

◆ createCollisionGroupAsSharedPtr() [1/2]

std::shared_ptr< CollisionGroup > dart::collision::CollisionDetector::createCollisionGroupAsSharedPtr ( )
inherited

Helper function that creates and returns CollisionGroup as a shared_ptr.

Internally, this function creates a shared_ptr from unique_ptr returned from createCollisionGroup() so the performance would be slighly worse than using std::make_unique.

◆ createCollisionGroupAsSharedPtr() [2/2]

template<typename... Args>
std::shared_ptr< CollisionGroup > dart::collision::CollisionDetector::createCollisionGroupAsSharedPtr ( const Args &...  args)
inherited

Helper function that creates and returns CollisionGroup as shared_ptr.

◆ createCollisionObject()

std::unique_ptr< CollisionObject > dart::collision::BulletCollisionDetector::createCollisionObject ( const dynamics::ShapeFrame shapeFrame)
overrideprotectedvirtual

◆ distance() [1/2]

double dart::collision::BulletCollisionDetector::distance ( CollisionGroup group,
const DistanceOption option = DistanceOption(false, 0.0, nullptr),
DistanceResult result = nullptr 
)
overridevirtual

Get the minimum signed distance between the Shape pairs in the given CollisionGroup.

The detailed results are stored in the given DistanceResult if provided.

The results can be different by DistanceOption. By default, non-negative minimum distance (distance >= 0) is returned for all the shape pairs without computing nearest points.

Implements dart::collision::CollisionDetector.

◆ distance() [2/2]

double dart::collision::BulletCollisionDetector::distance ( CollisionGroup group1,
CollisionGroup group2,
const DistanceOption option = DistanceOption(false, 0.0, nullptr),
DistanceResult result = nullptr 
)
overridevirtual

Get the minimum signed distance between the Shape pairs where a pair consist of two shapes from each groups (one from group1 and one from group2).

Note that the distance between shapes within the same CollisionGroup are not accounted.

The detailed results are stored in the given DistanceResult if provided.

The results can be different by DistanceOption. By default, non-negative minimum distance (distance >= 0) is returned for all the shape pairs without computing nearest points.

Implements dart::collision::CollisionDetector.

◆ getFactory()

CollisionDetector::Factory * dart::collision::CollisionDetector::getFactory ( )
staticinherited

Returns the singleton factory.

◆ getStaticType()

const std::string & dart::collision::BulletCollisionDetector::getStaticType ( )
static

Get collision detector type for this class.

◆ getType()

const std::string & dart::collision::BulletCollisionDetector::getType ( ) const
overridevirtual

Return collision detection engine type as a std::string.

Implements dart::collision::CollisionDetector.

◆ notifyCollisionObjectDestroying()

void dart::collision::BulletCollisionDetector::notifyCollisionObjectDestroying ( CollisionObject object)
overrideprotectedvirtual

Notify that a CollisionObject is destroying. Do nothing by default.

Reimplemented from dart::collision::CollisionDetector.

◆ reclaimBulletCollisionShape()

void dart::collision::BulletCollisionDetector::reclaimBulletCollisionShape ( const dynamics::ConstShapePtr shape)
private

◆ refreshCollisionObject()

void dart::collision::BulletCollisionDetector::refreshCollisionObject ( CollisionObject object)
overrideprotectedvirtual

Update the collision geometry of a ShapeFrame.

Implements dart::collision::CollisionDetector.

Friends And Related Function Documentation

◆ CollisionDetector

friend class CollisionDetector
friend

Member Data Documentation

◆ mCollisionObjectManager

std::unique_ptr<CollisionObjectManager> dart::collision::CollisionDetector::mCollisionObjectManager
protectedinherited

◆ mGroupForFiltering

std::unique_ptr<BulletCollisionGroup> dart::collision::BulletCollisionDetector::mGroupForFiltering
private

◆ mRegistrar

BulletCollisionDetector::Registrar< BulletCollisionDetector > dart::collision::BulletCollisionDetector::mRegistrar
staticprivate
Initial value:
{
[]() -> std::shared_ptr<dart::collision::BulletCollisionDetector> {
}}
static std::shared_ptr< BulletCollisionDetector > create()
Definition: BulletCollisionDetector.cpp:98
static const std::string & getStaticType()
Get collision detector type for this class.
Definition: BulletCollisionDetector.cpp:124

◆ mShapeMap

std::map<dynamics::ConstShapePtr, ShapeInfo> dart::collision::BulletCollisionDetector::mShapeMap
private