DART 6.6.2
|
#include <CollisionGroup.hpp>
Public Member Functions | |
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. | |
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. | |
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. | |
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. | |
void | addShapeFramesOf () |
Do nothing. | |
void | removeShapeFrame (const dynamics::ShapeFrame *shapeFrame) |
Remove a ShapeFrame from this CollisionGroup. | |
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. | |
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. | |
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. | |
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. | |
void | removeShapeFramesOf () |
Do nothing. | |
void | removeAllShapeFrames () |
Remove all the ShapeFrames in this CollisionGroup. | |
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::ShapeFrame * | getShapeFrame (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. | |
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. | |
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). | |
Protected Member Functions | |
void | updateEngineData () |
Update engine data. | |
virtual void | initializeEngineData ()=0 |
Initialize the collision detection engine data such as broadphase algorithm. | |
virtual void | addCollisionObjectToEngine (CollisionObject *object)=0 |
Add CollisionObject to the collision detection engine. | |
virtual void | addCollisionObjectsToEngine (const std::vector< CollisionObject * > &collObjects)=0 |
Add CollisionObjects to the collision detection engine. | |
virtual void | removeCollisionObjectFromEngine (CollisionObject *object)=0 |
Remove CollisionObject from the collision detection engine. | |
virtual void | removeAllCollisionObjectsFromEngine ()=0 |
Remove all the CollisionObjects from the collision detection engine. | |
virtual void | updateCollisionGroupEngineData ()=0 |
Update the collision detection engine data such as broadphase algorithm. | |
Protected Attributes | |
CollisionDetectorPtr | mCollisionDetector |
Collision detector. | |
std::vector< std::pair< const dynamics::ShapeFrame *, CollisionObjectPtr > > | mShapeFrameMap |
ShapeFrames and CollisionOjbects added to this CollisionGroup. | |
dart::collision::CollisionGroup::CollisionGroup | ( | const CollisionDetectorPtr & | collisionDetector | ) |
Constructor.
|
virtualdefault |
Destructor.
|
protectedpure virtual |
Add CollisionObjects to the collision detection engine.
Implemented in dart::collision::BulletCollisionGroup, dart::collision::DARTCollisionGroup, dart::collision::FCLCollisionGroup, and dart::collision::OdeCollisionGroup.
|
protectedpure virtual |
Add CollisionObject to the collision detection engine.
Implemented in dart::collision::BulletCollisionGroup, dart::collision::DARTCollisionGroup, dart::collision::FCLCollisionGroup, and dart::collision::OdeCollisionGroup.
void dart::collision::CollisionGroup::addShapeFrame | ( | const dynamics::ShapeFrame * | shapeFrame | ) |
Add a ShapeFrame to this CollisionGroup.
void dart::collision::CollisionGroup::addShapeFrames | ( | const std::vector< const dynamics::ShapeFrame * > & | shapeFrames | ) |
Add ShapeFrames to this CollisionGroup.
void dart::collision::CollisionGroup::addShapeFramesOf | ( | ) |
Do nothing.
This function is for terminating the recursive variadic template function template<typename...> addShapeFramesOf().
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.
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.
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.
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.
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.
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.
bool dart::collision::CollisionGroup::collide | ( | const CollisionOption & | option = CollisionOption(false, 1u, nullptr) , |
CollisionResult * | result = nullptr |
||
) |
Perform collision check within this CollisionGroup.
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.
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.
CollisionDetectorPtr dart::collision::CollisionGroup::getCollisionDetector | ( | ) |
Return collision detection engine associated with this CollisionGroup.
ConstCollisionDetectorPtr dart::collision::CollisionGroup::getCollisionDetector | ( | ) | const |
Return (const) collision detection engine associated with this CollisionGroup.
std::size_t dart::collision::CollisionGroup::getNumShapeFrames | ( | ) | const |
Return number of ShapeFrames added to this CollisionGroup.
const dynamics::ShapeFrame * dart::collision::CollisionGroup::getShapeFrame | ( | std::size_t | index | ) | const |
Get the ShapeFrame corresponding to the given index.
bool dart::collision::CollisionGroup::hasShapeFrame | ( | const dynamics::ShapeFrame * | shapeFrame | ) | const |
Return true if this CollisionGroup contains shapeFrame.
|
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::BulletCollisionGroup, dart::collision::DARTCollisionGroup, dart::collision::FCLCollisionGroup, and dart::collision::OdeCollisionGroup.
|
protectedpure virtual |
Remove all the CollisionObjects from the collision detection engine.
Implemented in dart::collision::BulletCollisionGroup, dart::collision::DARTCollisionGroup, dart::collision::FCLCollisionGroup, and dart::collision::OdeCollisionGroup.
void dart::collision::CollisionGroup::removeAllShapeFrames | ( | ) |
Remove all the ShapeFrames in this CollisionGroup.
|
protectedpure virtual |
Remove CollisionObject from the collision detection engine.
Implemented in dart::collision::BulletCollisionGroup, dart::collision::DARTCollisionGroup, dart::collision::FCLCollisionGroup, and dart::collision::OdeCollisionGroup.
void dart::collision::CollisionGroup::removeShapeFrame | ( | const dynamics::ShapeFrame * | shapeFrame | ) |
Remove a ShapeFrame from this CollisionGroup.
void dart::collision::CollisionGroup::removeShapeFrames | ( | const std::vector< const dynamics::ShapeFrame * > & | shapeFrames | ) |
Remove ShapeFrames from this CollisionGroup.
void dart::collision::CollisionGroup::removeShapeFramesOf | ( | ) |
Do nothing.
This function is for terminating the recursive variadic template function template<typename...> removeShapeFramesOf().
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.
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.
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.
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.
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.
|
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::BulletCollisionGroup, dart::collision::DARTCollisionGroup, dart::collision::FCLCollisionGroup, and dart::collision::OdeCollisionGroup.
|
protected |
Update engine data.
This function should be called before the collision detection is performed by the engine in most cases.
|
protected |
Collision detector.
|
protected |
ShapeFrames and CollisionOjbects added to this CollisionGroup.