#include <BulletPhysics.h>
Public Types | |
| enum | collisionShapeType_t { SHAPE_BOX, SHAPE_SPHERE, SHAPE_TRIMESH, SHAPE_COMPOUND_TRIMESH, SHAPE_COMPOUND_BOX, SHAPE_COMPOUND_CYLINDER } |
Public Member Functions | |
| btRigidBody * | addFloatingObject (osg::MatrixTransform *root, osg::Node *node, CollisionDataType *data, boost::shared_ptr< PhysicProperties > pp, osg::Node *colShape=NULL) |
| btRigidBody * | addObject (osg::MatrixTransform *root, osg::Node *node, CollisionDataType *data, boost::shared_ptr< PhysicProperties > pp, osg::Node *colShape=NULL) |
| BulletPhysics (double configGravity[3], osgOcean::OceanTechnique *oceanSurf, PhysicsWater physicsWater) | |
| btRigidBody * | copyObject (btRigidBody *copied) |
| btPersistentManifold * | getCollision (int i) |
| int | getNumCollisions () |
| void | printManifolds () |
| void | setGravity (btVector3 g) |
| void | stepSimulation (btScalar timeStep, int maxSubSteps, btScalar fixedTimeStep) |
| ~BulletPhysics () | |
Public Attributes | |
| btHfFluidRigidDynamicsWorld * | dynamicsWorld |
| int | physicsStep |
Private Member Functions | |
| void | cleanManifolds () |
| btConvexShape * | GetConvexCSFromOSG (osg::Node *node, collisionShapeType_t ctype) |
| btCollisionShape * | GetCSFromOSG (osg::Node *node, collisionShapeType_t ctype) |
| void | updateOceanSurface () |
Private Attributes | |
| btHfFluidRigidCollisionConfiguration * | collisionConfiguration |
| btCollisionDispatcher * | dispatcher |
| btHfFluid * | fluid |
| btBroadphaseInterface * | inter |
| osgOcean::OceanTechnique * | oceanSurface |
| btConstraintSolver * | solver |
Definition at line 74 of file BulletPhysics.h.
| SHAPE_BOX | |
| SHAPE_SPHERE | |
| SHAPE_TRIMESH | |
| SHAPE_COMPOUND_TRIMESH | |
| SHAPE_COMPOUND_BOX | |
| SHAPE_COMPOUND_CYLINDER |
Definition at line 78 of file BulletPhysics.h.
| BulletPhysics::BulletPhysics | ( | double | configGravity[3], |
| osgOcean::OceanTechnique * | oceanSurf, | ||
| PhysicsWater | physicsWater | ||
| ) |
Definition at line 160 of file BulletPhysics.cpp.
| BulletPhysics::~BulletPhysics | ( | ) | [inline] |
Definition at line 107 of file BulletPhysics.h.
| btRigidBody * BulletPhysics::addFloatingObject | ( | osg::MatrixTransform * | root, |
| osg::Node * | node, | ||
| CollisionDataType * | data, | ||
| boost::shared_ptr< PhysicProperties > | pp, | ||
| osg::Node * | colShape = NULL |
||
| ) |
Definition at line 385 of file BulletPhysics.cpp.
| btRigidBody * BulletPhysics::addObject | ( | osg::MatrixTransform * | root, |
| osg::Node * | node, | ||
| CollisionDataType * | data, | ||
| boost::shared_ptr< PhysicProperties > | pp, | ||
| osg::Node * | colShape = NULL |
||
| ) |
Definition at line 255 of file BulletPhysics.cpp.
| void BulletPhysics::cleanManifolds | ( | ) | [private] |
Definition at line 449 of file BulletPhysics.cpp.
| btRigidBody * BulletPhysics::copyObject | ( | btRigidBody * | copied | ) |
Definition at line 44 of file BulletPhysics.cpp.
| btPersistentManifold * BulletPhysics::getCollision | ( | int | i | ) |
Definition at line 444 of file BulletPhysics.cpp.
| btConvexShape * BulletPhysics::GetConvexCSFromOSG | ( | osg::Node * | node, |
| collisionShapeType_t | ctype | ||
| ) | [private] |
Definition at line 373 of file BulletPhysics.cpp.
| btCollisionShape * BulletPhysics::GetCSFromOSG | ( | osg::Node * | node, |
| collisionShapeType_t | ctype | ||
| ) | [private] |
Definition at line 235 of file BulletPhysics.cpp.
| int BulletPhysics::getNumCollisions | ( | ) |
Definition at line 439 of file BulletPhysics.cpp.
| void BulletPhysics::printManifolds | ( | ) |
Definition at line 135 of file BulletPhysics.cpp.
| void BulletPhysics::setGravity | ( | btVector3 | g | ) | [inline] |
Definition at line 88 of file BulletPhysics.h.
| void BulletPhysics::stepSimulation | ( | btScalar | timeStep, |
| int | maxSubSteps = 1, |
||
| btScalar | fixedTimeStep = btScalar(1.) / btScalar(60.) |
||
| ) |
Definition at line 122 of file BulletPhysics.cpp.
| void BulletPhysics::updateOceanSurface | ( | ) | [private] |
Definition at line 212 of file BulletPhysics.cpp.
Definition at line 110 of file BulletPhysics.h.
btCollisionDispatcher* BulletPhysics::dispatcher [private] |
Definition at line 114 of file BulletPhysics.h.
Definition at line 83 of file BulletPhysics.h.
btHfFluid* BulletPhysics::fluid [private] |
Definition at line 117 of file BulletPhysics.h.
btBroadphaseInterface* BulletPhysics::inter [private] |
Definition at line 116 of file BulletPhysics.h.
osgOcean::OceanTechnique* BulletPhysics::oceanSurface [private] |
Definition at line 119 of file BulletPhysics.h.
Definition at line 103 of file BulletPhysics.h.
btConstraintSolver* BulletPhysics::solver [private] |
Definition at line 115 of file BulletPhysics.h.