DART
6.10.1
|
#include <BulletCollisionObject.hpp>
Public Member Functions | |
btCollisionObject * | getBulletCollisionObject () |
Return Bullet collision object. More... | |
const btCollisionObject * | getBulletCollisionObject () const |
Return Bullet collision object. More... | |
CollisionDetector * | getCollisionDetector () |
Return collision detection engine associated with this CollisionObject. More... | |
const CollisionDetector * | getCollisionDetector () const |
Return collision detection engine associated with this CollisionObject. More... | |
const dynamics::ShapeFrame * | getShapeFrame () const |
Return the associated ShapeFrame. More... | |
dynamics::ConstShapePtr | getShape () const |
Return the associated Shape. More... | |
const Eigen::Isometry3d & | getTransform () const |
Return the transformation of this CollisionObject in world coordinates. More... | |
Protected Member Functions | |
BulletCollisionObject (CollisionDetector *collisionDetector, const dynamics::ShapeFrame *shapeFrame, const std::shared_ptr< BulletCollisionShape > &bulletCollisionShape) | |
Constructor. More... | |
void | updateEngineData () override |
Update the collision object of the collision detection engine. More... | |
Protected Attributes | |
std::shared_ptr< BulletCollisionShape > | mBulletCollisionShape |
Bullet collision object. More... | |
std::unique_ptr< btCollisionObject > | mBulletCollisionObject |
CollisionDetector * | mCollisionDetector |
Collision detector. More... | |
const dynamics::ShapeFrame * | mShapeFrame |
ShapeFrame. More... | |
Friends | |
class | BulletCollisionDetector |
|
protected |
Constructor.
btCollisionObject * dart::collision::BulletCollisionObject::getBulletCollisionObject | ( | ) |
Return Bullet collision object.
const btCollisionObject * dart::collision::BulletCollisionObject::getBulletCollisionObject | ( | ) | const |
Return Bullet collision object.
|
inherited |
Return collision detection engine associated with this CollisionObject.
|
inherited |
Return collision detection engine associated with this CollisionObject.
|
inherited |
Return the associated Shape.
|
inherited |
Return the associated ShapeFrame.
|
inherited |
Return the transformation of this CollisionObject in world coordinates.
|
overrideprotectedvirtual |
Update the collision object of the collision detection engine.
This function will be called ahead of every collision checking by CollisionGroup.
Implements dart::collision::CollisionObject.
|
friend |
|
protected |
|
protected |
Bullet collision object.
|
protectedinherited |
Collision detector.
|
protectedinherited |
ShapeFrame.