DART  6.10.1
dart::collision::BulletCollisionGroup Class Reference

#include <BulletCollisionGroup.hpp>

Inheritance diagram for dart::collision::BulletCollisionGroup:
dart::collision::CollisionGroup

Public Member Functions

 BulletCollisionGroup (const CollisionDetectorPtr &collisionDetector)
 Constructor. More...
 
virtual ~BulletCollisionGroup ()=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...
 
template<typename... Others>
void subscribeTo (const dynamics::ConstBodyNodePtr &bodyNode, const Others &... others)
 Add ShapeFrames of bodyNode, and also subscribe to the BodyNode so that the results from this CollisionGroup automatically reflect any changes that are made to bodyNode. More...
 
template<typename... Others>
void subscribeTo (const dynamics::ConstSkeletonPtr &skeleton, const Others &... others)
 Add ShapeFrames of skeleton, and also subscribe to the Skeleton so that the results from this CollisionGroup automatically reflect any changes that are made to skeleton. More...
 
void subscribeTo ()
 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...
 
template<typename... Others>
void unsubscribeFrom (const dynamics::BodyNode *bodyNode, const Others *... others)
 Unsubscribe from bodyNode. More...
 
template<typename... Others>
void unsubscribeFrom (const dynamics::Skeleton *skeleton, const Others *... others)
 Unsubscribe from skeleton. 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...
 
bool raycast (const Eigen::Vector3d &from, const Eigen::Vector3d &to, const RaycastOption &option=RaycastOption(), RaycastResult *result=nullptr)
 Performs raycast to this collision group. More...
 
void setAutomaticUpdate (bool automatic=true)
 Set whether this CollisionGroup will automatically check for updates. More...
 
bool getAutomaticUpdate () const
 Get whether this CollisionGroup is set to automatically check for updates. More...
 
void update ()
 Check whether this CollisionGroup's subscriptions or any of its objects need an update, and then update them if they do. More...
 
void removeDeletedShapeFrames ()
 Remove any ShapeFrames that have been deleted. More...
 

Protected Types

using ObjectInfoList = std::vector< std::unique_ptr< ObjectInfo > >
 

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...
 
btCollisionWorld * getBulletCollisionWorld ()
 Return Bullet collision world. More...
 
const btCollisionWorld * getBulletCollisionWorld () const
 Return Bullet collision world. More...
 
void updateEngineData ()
 Update engine data. More...
 

Protected Attributes

std::unique_ptr< btBroadphaseInterface > mBulletProadphaseAlg
 Bullet broad-phase algorithm. More...
 
std::unique_ptr< btCollisionConfiguration > mBulletCollisionConfiguration
 Bullet collision configuration. More...
 
std::unique_ptr< btDispatcher > mBulletDispatcher
 Bullet collision dispatcher. More...
 
std::unique_ptr< btCollisionWorld > mBulletCollisionWorld
 Bullet collision world. More...
 
CollisionDetectorPtr mCollisionDetector
 Collision detector. More...
 
ObjectInfoList mObjectInfoList
 Information about ShapeFrames and CollisionObjects that have been added to this CollisionGroup. More...
 

Private Types

using SkeletonSource = CollisionSource< dynamics::WeakConstMetaSkeletonPtr, dynamics::BodyNode >
 
using SkeletonSources = std::unordered_map< const dynamics::MetaSkeleton *, SkeletonSource >
 
using BodyNodeSource = CollisionSource< dynamics::WeakConstBodyNodePtr >
 
using BodyNodeSources = std::unordered_map< const dynamics::BodyNode *, BodyNodeSource >
 

Private Member Functions

ObjectInfoaddShapeFrameImpl (const dynamics::ShapeFrame *shapeFrame, const void *source)
 Implementation of addShapeFrame. More...
 
void removeShapeFrameInternal (const dynamics::ShapeFrame *shapeFrame, const void *source)
 Internal version of removeShapeFrame. More...
 
bool updateSkeletonSource (SkeletonSources::value_type &entry)
 Internal function called to update a Skeleton source. More...
 
bool updateBodyNodeSource (BodyNodeSources::value_type &entry)
 Internal function called to update a BodyNode source. More...
 
bool updateShapeFrame (ObjectInfo *object)
 Internal function called to update a ShapeFrame. More...
 

Private Attributes

bool mUpdateAutomatically
 Set this to true to have this CollisionGroup check for updates automatically. More...
 
SkeletonSources mSkeletonSources
 Skeleton sources that this group is subscribed to. More...
 
BodyNodeSources mBodyNodeSources
 BodyNode sources that this group is susbscribed to. More...
 
ShapeFrameObserver mObserver
 The object that observes the Shape Frames that this group cares about. More...
 

Friends

class BulletCollisionDetector
 

Member Typedef Documentation

◆ BodyNodeSource

◆ BodyNodeSources

using dart::collision::CollisionGroup::BodyNodeSources = std::unordered_map<const dynamics::BodyNode*, BodyNodeSource>
privateinherited

◆ ObjectInfoList

using dart::collision::CollisionGroup::ObjectInfoList = std::vector<std::unique_ptr<ObjectInfo> >
protectedinherited

◆ SkeletonSource

◆ SkeletonSources

using dart::collision::CollisionGroup::SkeletonSources = std::unordered_map<const dynamics::MetaSkeleton*, SkeletonSource>
privateinherited

Constructor & Destructor Documentation

◆ BulletCollisionGroup()

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

Constructor.

◆ ~BulletCollisionGroup()

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

Destructor.

Member Function Documentation

◆ addCollisionObjectsToEngine()

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

Add CollisionObjects to the collision detection engine.

Implements dart::collision::CollisionGroup.

◆ addCollisionObjectToEngine()

void dart::collision::BulletCollisionGroup::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.

◆ addShapeFrameImpl()

auto dart::collision::CollisionGroup::addShapeFrameImpl ( const dynamics::ShapeFrame shapeFrame,
const void *  source 
)
privateinherited

Implementation of addShapeFrame.

The source argument tells us whether this ShapeFrame is being requested explicitly by the user or implicitly through a BodyNode, Skeleton, or other 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.

◆ getAutomaticUpdate()

bool dart::collision::CollisionGroup::getAutomaticUpdate ( ) const
inherited

Get whether this CollisionGroup is set to automatically check for updates.

◆ getBulletCollisionWorld() [1/2]

btCollisionWorld * dart::collision::BulletCollisionGroup::getBulletCollisionWorld ( )
protected

Return Bullet collision world.

◆ getBulletCollisionWorld() [2/2]

const btCollisionWorld * dart::collision::BulletCollisionGroup::getBulletCollisionWorld ( ) const
protected

Return Bullet collision world.

◆ 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.

◆ 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::BulletCollisionGroup::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.

◆ raycast()

bool dart::collision::CollisionGroup::raycast ( const Eigen::Vector3d &  from,
const Eigen::Vector3d &  to,
const RaycastOption option = RaycastOption(),
RaycastResult result = nullptr 
)
inherited

Performs raycast to this collision group.

Parameters
[in]fromThe start point of the ray in world coordinates.
[in]toThe end point of the ray in world coordinates.
[in]optionThe raycast option.
[in]resultThe raycast result.
Returns
True if the ray hit an collision object.

◆ removeAllCollisionObjectsFromEngine()

void dart::collision::BulletCollisionGroup::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::BulletCollisionGroup::removeCollisionObjectFromEngine ( CollisionObject object)
overrideprotectedvirtual

Remove CollisionObject from the collision detection engine.

Implements dart::collision::CollisionGroup.

◆ removeDeletedShapeFrames()

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

Remove any ShapeFrames that have been deleted.

This will be done automatically for ShapeFrames that belong to subscriptions.

Returns true if one or more ShapeFrames were removed; otherwise returns false.

◆ removeShapeFrame()

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

Remove a ShapeFrame from this CollisionGroup.

If this ShapeFrame was being provided by any subscriptions, then calling this function will unsubscribe from those subscriptions, because otherwise this ShapeFrame would simply be put back into the CollisionGroup the next time the group gets updated.

◆ removeShapeFrameInternal()

void dart::collision::CollisionGroup::removeShapeFrameInternal ( const dynamics::ShapeFrame shapeFrame,
const void *  source 
)
privateinherited

Internal version of removeShapeFrame.

This will only remove the ShapeFrame if it is unsubscribed from all sources.

◆ 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.

If this CollisionGroup is subscribed to otherGroup, then this function will also unsubscribe from it.

◆ 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.

If this CollisionGroup is subscribed to bodyNode, then this function will also unsubscribe from it.

◆ 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.

If this CollisionGroup is subscribed to skeleton, then this function will also unsubscribe from it.

◆ 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.

◆ setAutomaticUpdate()

void dart::collision::CollisionGroup::setAutomaticUpdate ( bool  automatic = true)
inherited

Set whether this CollisionGroup will automatically check for updates.

◆ subscribeTo() [1/3]

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

Do nothing.

This function is for terminating the recursive variadic template.

◆ subscribeTo() [2/3]

template<typename... Others>
void dart::collision::CollisionGroup::subscribeTo ( const dynamics::ConstBodyNodePtr bodyNode,
const Others &...  others 
)
inherited

Add ShapeFrames of bodyNode, and also subscribe to the BodyNode so that the results from this CollisionGroup automatically reflect any changes that are made to bodyNode.

This does likewise for the objects in ...others.

◆ subscribeTo() [3/3]

template<typename... Others>
void dart::collision::CollisionGroup::subscribeTo ( const dynamics::ConstSkeletonPtr skeleton,
const Others &...  others 
)
inherited

Add ShapeFrames of skeleton, and also subscribe to the Skeleton so that the results from this CollisionGroup automatically reflect any changes that are made to skeleton.

This does likewise for the objects in ...others.

◆ unsubscribeFrom() [1/2]

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

Unsubscribe from bodyNode.

The ShapeFrames of the BodyNode will also be removed if no other source is requesting them for this group.

◆ unsubscribeFrom() [2/2]

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

Unsubscribe from skeleton.

The ShapeFrames of the skeleton will also be removed if no other source is requesting them for this group.

◆ update()

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

Check whether this CollisionGroup's subscriptions or any of its objects need an update, and then update them if they do.

If automatic updating is turned on, then this will be called each time collide() is.

This can be called manually in order to control when collision objects get created or destroyed. Those procedures can be time-consuming, so it may be useful to control when it occurs.

◆ updateBodyNodeSource()

bool dart::collision::CollisionGroup::updateBodyNodeSource ( BodyNodeSources::value_type &  entry)
privateinherited

Internal function called to update a BodyNode source.

Returns
true if an update was performed

◆ updateCollisionGroupEngineData()

void dart::collision::BulletCollisionGroup::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.

◆ updateShapeFrame()

bool dart::collision::CollisionGroup::updateShapeFrame ( ObjectInfo object)
privateinherited

Internal function called to update a ShapeFrame.

Returns
true if an update was performed

◆ updateSkeletonSource()

bool dart::collision::CollisionGroup::updateSkeletonSource ( SkeletonSources::value_type &  entry)
privateinherited

Internal function called to update a Skeleton source.

Returns
true if an update was performed

Friends And Related Function Documentation

◆ BulletCollisionDetector

friend class BulletCollisionDetector
friend

Member Data Documentation

◆ mBodyNodeSources

BodyNodeSources dart::collision::CollisionGroup::mBodyNodeSources
privateinherited

BodyNode sources that this group is susbscribed to.

◆ mBulletCollisionConfiguration

std::unique_ptr<btCollisionConfiguration> dart::collision::BulletCollisionGroup::mBulletCollisionConfiguration
protected

Bullet collision configuration.

◆ mBulletCollisionWorld

std::unique_ptr<btCollisionWorld> dart::collision::BulletCollisionGroup::mBulletCollisionWorld
protected

Bullet collision world.

◆ mBulletDispatcher

std::unique_ptr<btDispatcher> dart::collision::BulletCollisionGroup::mBulletDispatcher
protected

Bullet collision dispatcher.

◆ mBulletProadphaseAlg

std::unique_ptr<btBroadphaseInterface> dart::collision::BulletCollisionGroup::mBulletProadphaseAlg
protected

Bullet broad-phase algorithm.

◆ mCollisionDetector

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

Collision detector.

◆ mObjectInfoList

ObjectInfoList dart::collision::CollisionGroup::mObjectInfoList
protectedinherited

Information about ShapeFrames and CollisionObjects that have been added to this CollisionGroup.

◆ mObserver

ShapeFrameObserver dart::collision::CollisionGroup::mObserver
privateinherited

The object that observes the Shape Frames that this group cares about.

◆ mSkeletonSources

SkeletonSources dart::collision::CollisionGroup::mSkeletonSources
privateinherited

Skeleton sources that this group is subscribed to.

◆ mUpdateAutomatically

bool dart::collision::CollisionGroup::mUpdateAutomatically
privateinherited

Set this to true to have this CollisionGroup check for updates automatically.

Default is true.