dart
Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
dart::collision::OdeCollisionGroup Class Reference
Inheritance diagram for dart::collision::OdeCollisionGroup:
Inheritance graph
[legend]
Collaboration diagram for dart::collision::OdeCollisionGroup:
Collaboration graph
[legend]

Public Member Functions

 OdeCollisionGroup (const CollisionDetectorPtr &collisionDetector)
 Constructor.
 
virtual ~OdeCollisionGroup ()
 Destructor.
 
- Public Member Functions inherited from dart::collision::CollisionGroup
 CollisionGroup (const CollisionDetectorPtr &collisionDetector)
 Constructor.
 
virtual ~CollisionGroup ()=default
 Destructor.
 
CollisionDetectorPtr getCollisionDetector ()
 Return collision detection engine associated with this CollisionGroup.
 
ConstCollisionDetectorPtr getCollisionDetector () const
 Return (const) collision detection engine associated with this CollisionGroup.
 
void addShapeFrame (const dynamics::ShapeFrame *shapeFrame)
 Add a ShapeFrame to this CollisionGroup.
 
void addShapeFrames (const std::vector< const dynamics::ShapeFrame *> &shapeFrames)
 Add ShapeFrames to this CollisionGroup.
 
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.
 
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.
 
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.
 
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.
 
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.
 
std::size_t getNumShapeFrames () const
 Return number of ShapeFrames added to this CollisionGroup.
 
const dynamics::ShapeFramegetShapeFrame (std::size_t index) const
 Get the ShapeFrame corresponding to the given index.
 
bool collide (const CollisionOption &option=CollisionOption(false, 1u, nullptr), CollisionResult *result=nullptr)
 Perform collision check within this CollisionGroup.
 
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.
 
bool getAutomaticUpdate () const
 Get whether this CollisionGroup is set to automatically check for updates.
 
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 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.
 
void addCollisionObjectsToEngine (const std::vector< CollisionObject *> &collObjects) override
 Add CollisionObjects to the collision detection engine.
 
void removeCollisionObjectFromEngine (CollisionObject *object) override
 Remove CollisionObject from the collision detection engine.
 
void removeAllCollisionObjectsFromEngine () override
 Remove all the CollisionObjects from the collision detection engine.
 
void updateCollisionGroupEngineData () override
 Update the collision detection engine data such as broadphase algorithm. More...
 
dSpaceID getOdeSpaceId () const
 Returns ODE space id associated with this collision group.
 
- Protected Member Functions inherited from dart::collision::CollisionGroup
void updateEngineData ()
 Update engine data. More...
 

Protected Attributes

dSpaceID mSpaceId
 Top-level space for all sub-spaces/collisions.
 
- Protected Attributes inherited from dart::collision::CollisionGroup
CollisionDetectorPtr mCollisionDetector
 Collision detector.
 
ObjectInfoList mObjectInfoList
 Information about ShapeFrames and CollisionObjects that have been added to this CollisionGroup. More...
 

Friends

class OdeCollisionDetector
 

Additional Inherited Members

- Protected Types inherited from dart::collision::CollisionGroup
using ObjectInfoList = std::vector< std::unique_ptr< ObjectInfo > >
 

Member Function Documentation

◆ initializeEngineData()

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

◆ updateCollisionGroupEngineData()

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


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