DART  6.6.2
dart::collision::FCLCollisionGroup Class Reference

#include <FCLCollisionGroup.hpp>

Inheritance diagram for dart::collision::FCLCollisionGroup:
dart::collision::CollisionGroup

Public Types

using FCLCollisionManager = dart::collision::fcl::DynamicAABBTreeCollisionManager
 

Public Member Functions

 FCLCollisionGroup (const CollisionDetectorPtr &collisionDetector)
 Constructor. More...
 
virtual ~FCLCollisionGroup ()=default
 Destructor. More...
 
CollisionDetectorPtr getCollisionDetector ()
 Return collision detection engine associated with this CollisionGroup. More...
 
ConstCollisionDetectorPtr getCollisionDetector () const
 Return (const) collision detection engine associated with this CollisionGroup. More...
 
void addShapeFrame (const dynamics::ShapeFrame *shapeFrame)
 Add a ShapeFrame to this CollisionGroup. More...
 
void addShapeFrames (const std::vector< const dynamics::ShapeFrame * > &shapeFrames)
 Add ShapeFrames to this CollisionGroup. More...
 
template<typename... Others>
void addShapeFramesOf (const dynamics::ShapeFrame *shapeFrame, const Others *... others)
 Add a ShapeFrame, and also add ShapeFrames of other various objects. More...
 
template<typename... Others>
void addShapeFramesOf (const std::vector< const dynamics::ShapeFrame * > &shapeFrames, const Others *... others)
 Add ShapeFrames, and also add ShapeFrames of other various objects. More...
 
template<typename... Others>
void addShapeFramesOf (const CollisionGroup *otherGroup, const Others *... others)
 Add ShapeFrames of other CollisionGroup, and also add another ShapeFrames of other various objects. More...
 
template<typename... Others>
void addShapeFramesOf (const dynamics::BodyNode *bodyNode, const Others *... others)
 Add ShapeFrames of BodyNode, and also add another ShapeFrames of other various objects. More...
 
template<typename... Others>
void addShapeFramesOf (const dynamics::MetaSkeleton *skeleton, const Others *... others)
 Add ShapeFrames of MetaSkeleton, and also add another ShapeFrames of other various objects. More...
 
void addShapeFramesOf ()
 Do nothing. More...
 
void removeShapeFrame (const dynamics::ShapeFrame *shapeFrame)
 Remove a ShapeFrame from this CollisionGroup. More...
 
void removeShapeFrames (const std::vector< const dynamics::ShapeFrame * > &shapeFrames)
 Remove ShapeFrames from this CollisionGroup. More...
 
template<typename... Others>
void removeShapeFramesOf (const dynamics::ShapeFrame *shapeFrame, const Others *... others)
 Remove a ShapeFrame, and also remove ShapeFrames of other various objects. More...
 
template<typename... Others>
void removeShapeFramesOf (const std::vector< const dynamics::ShapeFrame * > &shapeFrames, const Others *... others)
 Remove ShapeFrames, and also remove ShapeFrames of other various objects. More...
 
template<typename... Others>
void removeShapeFramesOf (const CollisionGroup *otherGroup, const Others *... others)
 Remove ShapeFrames of other CollisionGroup, and also remove another ShapeFrames of other various objects. More...
 
template<typename... Others>
void removeShapeFramesOf (const dynamics::BodyNode *bodyNode, const Others *... others)
 Remove ShapeFrames of BodyNode, and also remove another ShapeFrames of other various objects. More...
 
template<typename... Others>
void removeShapeFramesOf (const dynamics::MetaSkeleton *skeleton, const Others *... others)
 Remove ShapeFrames of MetaSkeleton, and also remove another ShapeFrames of other various objects. More...
 
void removeShapeFramesOf ()
 Do nothing. More...
 
void removeAllShapeFrames ()
 Remove all the ShapeFrames in this CollisionGroup. More...
 
bool hasShapeFrame (const dynamics::ShapeFrame *shapeFrame) const
 Return true if this CollisionGroup contains shapeFrame. More...
 
std::size_t getNumShapeFrames () const
 Return number of ShapeFrames added to this CollisionGroup. More...
 
const dynamics::ShapeFramegetShapeFrame (std::size_t index) const
 Get the ShapeFrame corresponding to the given index. More...
 
bool collide (const CollisionOption &option=CollisionOption(false, 1u, nullptr), CollisionResult *result=nullptr)
 Perform collision check within this CollisionGroup. More...
 
bool collide (CollisionGroup *otherGroup, const CollisionOption &option=CollisionOption(false, 1u, nullptr), CollisionResult *result=nullptr)
 Perform collision check with other CollisionGroup. More...
 
double distance (const DistanceOption &option=DistanceOption(false, 0.0, nullptr), DistanceResult *result=nullptr)
 Get the minimum signed distance between the Shape pairs in this CollisionGroup. More...
 
double distance (CollisionGroup *otherGroup, const DistanceOption &option=DistanceOption(false, 0.0, nullptr), DistanceResult *result=nullptr)
 Get the minimum signed distance between the Shape pairs where a pair consist of two shapes from each groups (one from this CollisionGroup and one from otherGroup). More...
 

Protected Member Functions

void initializeEngineData () override
 Initialize the collision detection engine data such as broadphase algorithm. More...
 
void addCollisionObjectToEngine (CollisionObject *object) override
 Add CollisionObject to the collision detection engine. More...
 
void addCollisionObjectsToEngine (const std::vector< CollisionObject * > &collObjects) override
 Add CollisionObjects to the collision detection engine. More...
 
void removeCollisionObjectFromEngine (CollisionObject *object) override
 Remove CollisionObject from the collision detection engine. More...
 
void removeAllCollisionObjectsFromEngine () override
 Remove all the CollisionObjects from the collision detection engine. More...
 
void updateCollisionGroupEngineData () override
 Update the collision detection engine data such as broadphase algorithm. More...
 
FCLCollisionManagergetFCLCollisionManager ()
 Return FCL collision manager that is also a broad-phase algorithm. More...
 
const FCLCollisionManagergetFCLCollisionManager () const
 Return FCL collision manager that is also a broad-phase algorithm. More...
 
void updateEngineData ()
 Update engine data. More...
 

Protected Attributes

std::unique_ptr< FCLCollisionManagermBroadPhaseAlg
 FCL broad-phase algorithm. More...
 
CollisionDetectorPtr mCollisionDetector
 Collision detector. More...
 
std::vector< std::pair< const dynamics::ShapeFrame *, CollisionObjectPtr > > mShapeFrameMap
 ShapeFrames and CollisionOjbects added to this CollisionGroup. More...
 

Friends

class FCLCollisionDetector
 

Member Typedef Documentation

◆ FCLCollisionManager

Constructor & Destructor Documentation

◆ FCLCollisionGroup()

dart::collision::FCLCollisionGroup::FCLCollisionGroup ( const CollisionDetectorPtr collisionDetector)

Constructor.

◆ ~FCLCollisionGroup()

virtual dart::collision::FCLCollisionGroup::~FCLCollisionGroup ( )
virtualdefault

Destructor.

Member Function Documentation

◆ addCollisionObjectsToEngine()

void dart::collision::FCLCollisionGroup::addCollisionObjectsToEngine ( const std::vector< CollisionObject * > &  collObjects)
overrideprotectedvirtual

Add CollisionObjects to the collision detection engine.

Implements dart::collision::CollisionGroup.

◆ addCollisionObjectToEngine()

void dart::collision::FCLCollisionGroup::addCollisionObjectToEngine ( CollisionObject object)
overrideprotectedvirtual

Add CollisionObject to the collision detection engine.

Implements dart::collision::CollisionGroup.

◆ addShapeFrame()

void dart::collision::CollisionGroup::addShapeFrame ( const dynamics::ShapeFrame shapeFrame)
inherited

Add a ShapeFrame to this CollisionGroup.

◆ addShapeFrames()

void dart::collision::CollisionGroup::addShapeFrames ( const std::vector< const dynamics::ShapeFrame * > &  shapeFrames)
inherited

Add ShapeFrames to this CollisionGroup.

◆ addShapeFramesOf() [1/6]

void dart::collision::CollisionGroup::addShapeFramesOf ( )
inherited

Do nothing.

This function is for terminating the recursive variadic template function template<typename...> addShapeFramesOf().

◆ addShapeFramesOf() [2/6]

template<typename... Others>
void dart::collision::CollisionGroup::addShapeFramesOf ( const CollisionGroup otherGroup,
const Others *...  others 
)
inherited

Add ShapeFrames of other CollisionGroup, and also add another ShapeFrames of other various objects.

◆ addShapeFramesOf() [3/6]

template<typename... Others>
void dart::collision::CollisionGroup::addShapeFramesOf ( const dynamics::BodyNode bodyNode,
const Others *...  others 
)
inherited

Add ShapeFrames of BodyNode, and also add another ShapeFrames of other various objects.

◆ addShapeFramesOf() [4/6]

template<typename... Others>
void dart::collision::CollisionGroup::addShapeFramesOf ( const dynamics::MetaSkeleton skeleton,
const Others *...  others 
)
inherited

Add ShapeFrames of MetaSkeleton, and also add another ShapeFrames of other various objects.

◆ addShapeFramesOf() [5/6]

template<typename... Others>
void dart::collision::CollisionGroup::addShapeFramesOf ( const dynamics::ShapeFrame shapeFrame,
const Others *...  others 
)
inherited

Add a ShapeFrame, and also add ShapeFrames of other various objects.

The other various 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 of this function is called. The aftwerward changes of the objects does not affect on this CollisionGroup.

◆ addShapeFramesOf() [6/6]

template<typename... Others>
void dart::collision::CollisionGroup::addShapeFramesOf ( const std::vector< const dynamics::ShapeFrame * > &  shapeFrames,
const Others *...  others 
)
inherited

Add ShapeFrames, and also add ShapeFrames of other various objects.

◆ collide() [1/2]

bool dart::collision::CollisionGroup::collide ( CollisionGroup otherGroup,
const CollisionOption option = CollisionOption(false, 1u, nullptr),
CollisionResult result = nullptr 
)
inherited

Perform collision check with other CollisionGroup.

Return false if the engine type of the other CollisionGroup is different from this CollisionObject engine.

◆ collide() [2/2]

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

Perform collision check within this CollisionGroup.

◆ distance() [1/2]

double dart::collision::CollisionGroup::distance ( CollisionGroup otherGroup,
const DistanceOption option = DistanceOption(false, 0.0, nullptr),
DistanceResult result = nullptr 
)
inherited

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

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.

◆ distance() [2/2]

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

Get the minimum signed distance between the Shape pairs in this 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.

◆ getCollisionDetector() [1/2]

CollisionDetectorPtr dart::collision::CollisionGroup::getCollisionDetector ( )
inherited

Return collision detection engine associated with this CollisionGroup.

◆ getCollisionDetector() [2/2]

ConstCollisionDetectorPtr dart::collision::CollisionGroup::getCollisionDetector ( ) const
inherited

Return (const) collision detection engine associated with this CollisionGroup.

◆ getFCLCollisionManager() [1/2]

FCLCollisionGroup::FCLCollisionManager * dart::collision::FCLCollisionGroup::getFCLCollisionManager ( )
protected

Return FCL collision manager that is also a broad-phase algorithm.

◆ getFCLCollisionManager() [2/2]

const FCLCollisionGroup::FCLCollisionManager * dart::collision::FCLCollisionGroup::getFCLCollisionManager ( ) const
protected

Return FCL collision manager that is also a broad-phase algorithm.

◆ getNumShapeFrames()

std::size_t dart::collision::CollisionGroup::getNumShapeFrames ( ) const
inherited

Return number of ShapeFrames added to this CollisionGroup.

◆ getShapeFrame()

const dynamics::ShapeFrame * dart::collision::CollisionGroup::getShapeFrame ( std::size_t  index) const
inherited

Get the ShapeFrame corresponding to the given index.

◆ hasShapeFrame()

bool dart::collision::CollisionGroup::hasShapeFrame ( const dynamics::ShapeFrame shapeFrame) const
inherited

Return true if this CollisionGroup contains shapeFrame.

◆ initializeEngineData()

void dart::collision::FCLCollisionGroup::initializeEngineData ( )
overrideprotectedvirtual

Initialize the collision detection engine data such as broadphase algorithm.

This function will be called whenever ShapeFrame is either added to or removed from this CollisionGroup.

Implements dart::collision::CollisionGroup.

◆ removeAllCollisionObjectsFromEngine()

void dart::collision::FCLCollisionGroup::removeAllCollisionObjectsFromEngine ( )
overrideprotectedvirtual

Remove all the CollisionObjects from the collision detection engine.

Implements dart::collision::CollisionGroup.

◆ removeAllShapeFrames()

void dart::collision::CollisionGroup::removeAllShapeFrames ( )
inherited

Remove all the ShapeFrames in this CollisionGroup.

◆ removeCollisionObjectFromEngine()

void dart::collision::FCLCollisionGroup::removeCollisionObjectFromEngine ( CollisionObject object)
overrideprotectedvirtual

Remove CollisionObject from the collision detection engine.

Implements dart::collision::CollisionGroup.

◆ removeShapeFrame()

void dart::collision::CollisionGroup::removeShapeFrame ( const dynamics::ShapeFrame shapeFrame)
inherited

Remove a ShapeFrame from this CollisionGroup.

◆ removeShapeFrames()

void dart::collision::CollisionGroup::removeShapeFrames ( const std::vector< const dynamics::ShapeFrame * > &  shapeFrames)
inherited

Remove ShapeFrames from this CollisionGroup.

◆ removeShapeFramesOf() [1/6]

void dart::collision::CollisionGroup::removeShapeFramesOf ( )
inherited

Do nothing.

This function is for terminating the recursive variadic template function template<typename...> removeShapeFramesOf().

◆ removeShapeFramesOf() [2/6]

template<typename... Others>
void dart::collision::CollisionGroup::removeShapeFramesOf ( const CollisionGroup otherGroup,
const Others *...  others 
)
inherited

Remove ShapeFrames of other CollisionGroup, and also remove another ShapeFrames of other various objects.

◆ removeShapeFramesOf() [3/6]

template<typename... Others>
void dart::collision::CollisionGroup::removeShapeFramesOf ( const dynamics::BodyNode bodyNode,
const Others *...  others 
)
inherited

Remove ShapeFrames of BodyNode, and also remove another ShapeFrames of other various objects.

◆ removeShapeFramesOf() [4/6]

template<typename... Others>
void dart::collision::CollisionGroup::removeShapeFramesOf ( const dynamics::MetaSkeleton skeleton,
const Others *...  others 
)
inherited

Remove ShapeFrames of MetaSkeleton, and also remove another ShapeFrames of other various objects.

◆ removeShapeFramesOf() [5/6]

template<typename... Others>
void dart::collision::CollisionGroup::removeShapeFramesOf ( const dynamics::ShapeFrame shapeFrame,
const Others *...  others 
)
inherited

Remove a ShapeFrame, and also remove ShapeFrames of other various objects.

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

Note that this function removes only the ShapeFrames of each object at the moment of this function is called. The aftwerward changes of the objects does not affect on this CollisionGroup.

◆ removeShapeFramesOf() [6/6]

template<typename... Others>
void dart::collision::CollisionGroup::removeShapeFramesOf ( const std::vector< const dynamics::ShapeFrame * > &  shapeFrames,
const Others *...  others 
)
inherited

Remove ShapeFrames, and also remove ShapeFrames of other various objects.

◆ updateCollisionGroupEngineData()

void dart::collision::FCLCollisionGroup::updateCollisionGroupEngineData ( )
overrideprotectedvirtual

Update the collision detection engine data such as broadphase algorithm.

This function will be called ahead of every collision checking.

Implements dart::collision::CollisionGroup.

◆ updateEngineData()

void dart::collision::CollisionGroup::updateEngineData
protected

Update engine data.

This function should be called before the collision detection is performed by the engine in most cases.

Friends And Related Function Documentation

◆ FCLCollisionDetector

friend class FCLCollisionDetector
friend

Member Data Documentation

◆ mBroadPhaseAlg

std::unique_ptr<FCLCollisionManager> dart::collision::FCLCollisionGroup::mBroadPhaseAlg
protected

FCL broad-phase algorithm.

◆ mCollisionDetector

CollisionDetectorPtr dart::collision::CollisionGroup::mCollisionDetector
protectedinherited

Collision detector.

◆ mShapeFrameMap

std::vector<std::pair<const dynamics::ShapeFrame*, CollisionObjectPtr> > dart::collision::CollisionGroup::mShapeFrameMap
protectedinherited

ShapeFrames and CollisionOjbects added to this CollisionGroup.