DART  6.10.1
dart::collision::CollisionGroup Class Referenceabstract

#include <CollisionGroup.hpp>

Inheritance diagram for dart::collision::CollisionGroup:
dart::collision::BulletCollisionGroup dart::collision::DARTCollisionGroup dart::collision::FCLCollisionGroup dart::collision::OdeCollisionGroup

Classes

struct  CollisionSource
 This struct is used to store sources of ShapeFrames that the CollisionGroup is subscribed to, alongside the last version number of that source, as known by this CollisionGroup. More...
 
struct  ObjectInfo
 Information on a collision object belonging to this group. More...
 
class  ShapeFrameObserver
 This class watches when ShapeFrames get deleted so that they can be safely removes from the CollisionGroup. More...
 

Public Member Functions

 CollisionGroup (const CollisionDetectorPtr &collisionDetector)
 Constructor. More...
 
virtual ~CollisionGroup ()=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 updateEngineData ()
 Update engine data. More...
 
virtual void initializeEngineData ()=0
 Initialize the collision detection engine data such as broadphase algorithm. More...
 
virtual void addCollisionObjectToEngine (CollisionObject *object)=0
 Add CollisionObject to the collision detection engine. More...
 
virtual void addCollisionObjectsToEngine (const std::vector< CollisionObject * > &collObjects)=0
 Add CollisionObjects to the collision detection engine. More...
 
virtual void removeCollisionObjectFromEngine (CollisionObject *object)=0
 Remove CollisionObject from the collision detection engine. More...
 
virtual void removeAllCollisionObjectsFromEngine ()=0
 Remove all the CollisionObjects from the collision detection engine. More...
 
virtual void updateCollisionGroupEngineData ()=0
 Update the collision detection engine data such as broadphase algorithm. More...
 

Protected Attributes

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

Member Typedef Documentation

◆ BodyNodeSource

◆ BodyNodeSources

◆ ObjectInfoList

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

◆ SkeletonSource

◆ SkeletonSources

Constructor & Destructor Documentation

◆ CollisionGroup()

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

Constructor.

◆ ~CollisionGroup()

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

Destructor.

Member Function Documentation

◆ addCollisionObjectsToEngine()

virtual void dart::collision::CollisionGroup::addCollisionObjectsToEngine ( const std::vector< CollisionObject * > &  collObjects)
protectedpure virtual

◆ addCollisionObjectToEngine()

virtual void dart::collision::CollisionGroup::addCollisionObjectToEngine ( CollisionObject object)
protectedpure virtual

◆ addShapeFrame()

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

Add a ShapeFrame to this CollisionGroup.

◆ addShapeFrameImpl()

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

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)

Add ShapeFrames to this CollisionGroup.

◆ addShapeFramesOf() [1/6]

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

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 
)

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 
)

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 
)

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 
)

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 
)

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 
)

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 
)

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 
)

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 
)

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

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

◆ getCollisionDetector() [1/2]

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

Return collision detection engine associated with this CollisionGroup.

◆ getCollisionDetector() [2/2]

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

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

◆ getNumShapeFrames()

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

Return number of ShapeFrames added to this CollisionGroup.

◆ getShapeFrame()

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

Get the ShapeFrame corresponding to the given index.

◆ hasShapeFrame()

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

Return true if this CollisionGroup contains shapeFrame.

◆ initializeEngineData()

virtual void dart::collision::CollisionGroup::initializeEngineData ( )
protectedpure virtual

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.

Implemented in dart::collision::OdeCollisionGroup, dart::collision::FCLCollisionGroup, dart::collision::DARTCollisionGroup, and dart::collision::BulletCollisionGroup.

◆ raycast()

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

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()

virtual void dart::collision::CollisionGroup::removeAllCollisionObjectsFromEngine ( )
protectedpure virtual

Remove all the CollisionObjects from the collision detection engine.

Implemented in dart::collision::OdeCollisionGroup, dart::collision::FCLCollisionGroup, dart::collision::DARTCollisionGroup, and dart::collision::BulletCollisionGroup.

◆ removeAllShapeFrames()

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

Remove all the ShapeFrames in this CollisionGroup.

◆ removeCollisionObjectFromEngine()

virtual void dart::collision::CollisionGroup::removeCollisionObjectFromEngine ( CollisionObject object)
protectedpure virtual

◆ removeDeletedShapeFrames()

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

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)

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 
)
private

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)

Remove ShapeFrames from this CollisionGroup.

◆ removeShapeFramesOf() [1/6]

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

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 
)

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 
)

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 
)

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 
)

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 
)

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

◆ setAutomaticUpdate()

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

Set whether this CollisionGroup will automatically check for updates.

◆ subscribeTo() [1/3]

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

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 
)

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 
)

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 
)

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 
)

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 ( )

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)
private

Internal function called to update a BodyNode source.

Returns
true if an update was performed

◆ updateCollisionGroupEngineData()

virtual void dart::collision::CollisionGroup::updateCollisionGroupEngineData ( )
protectedpure virtual

Update the collision detection engine data such as broadphase algorithm.

This function will be called ahead of every collision checking.

Implemented in dart::collision::OdeCollisionGroup, dart::collision::FCLCollisionGroup, dart::collision::DARTCollisionGroup, and dart::collision::BulletCollisionGroup.

◆ 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)
private

Internal function called to update a ShapeFrame.

Returns
true if an update was performed

◆ updateSkeletonSource()

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

Internal function called to update a Skeleton source.

Returns
true if an update was performed

Member Data Documentation

◆ mBodyNodeSources

BodyNodeSources dart::collision::CollisionGroup::mBodyNodeSources
private

BodyNode sources that this group is susbscribed to.

◆ mCollisionDetector

CollisionDetectorPtr dart::collision::CollisionGroup::mCollisionDetector
protected

Collision detector.

◆ mObjectInfoList

ObjectInfoList dart::collision::CollisionGroup::mObjectInfoList
protected

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

◆ mObserver

ShapeFrameObserver dart::collision::CollisionGroup::mObserver
private

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

◆ mSkeletonSources

SkeletonSources dart::collision::CollisionGroup::mSkeletonSources
private

Skeleton sources that this group is subscribed to.

◆ mUpdateAutomatically

bool dart::collision::CollisionGroup::mUpdateAutomatically
private

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

Default is true.