Go to the documentation of this file.00001
00031 #include <btBulletDynamicsCommon.h>
00032
00033 struct DynamicsWorldHandle
00034 {
00035 btBroadphaseInterface *broadphase;
00036 btCollisionConfiguration *collisionConfiguration;
00037 btCollisionDispatcher *dispatcher;
00038 btConstraintSolver *solver;
00039 btDynamicsWorld *dynamicsWorld;
00040 };
00041
00042 double bulletWorldScalingFactor = 1;
00043
00044 extern "C"
00045 {
00046 DynamicsWorldHandle *newDiscreteDynamicsWorld(double *gravityVector)
00047 {
00048 DynamicsWorldHandle *handle = new DynamicsWorldHandle;
00049 handle->broadphase = new btDbvtBroadphase();
00050 handle->collisionConfiguration = new btDefaultCollisionConfiguration();
00051 handle->dispatcher = new btCollisionDispatcher(handle->collisionConfiguration);
00052 handle->solver = new btSequentialImpulseConstraintSolver;
00053 handle->dynamicsWorld = new btDiscreteDynamicsWorld(handle->dispatcher,
00054 handle->broadphase,
00055 handle->solver,
00056 handle->collisionConfiguration);
00057 handle->dynamicsWorld->setGravity(
00058 btVector3(
00059 gravityVector[0] * bulletWorldScalingFactor,
00060 gravityVector[1] * bulletWorldScalingFactor,
00061 gravityVector[2] * bulletWorldScalingFactor));
00062
00063 return handle;
00064 }
00065
00066 void deleteDiscreteDynamicsWorld(DynamicsWorldHandle *handle)
00067 {
00068 delete handle->dynamicsWorld;
00069 delete handle->solver;
00070 delete handle->dispatcher;
00071 delete handle->collisionConfiguration;
00072 delete handle->broadphase;
00073 delete handle;
00074 }
00075
00076 void getGravity(DynamicsWorldHandle *handle, double *gravity)
00077 {
00078 btVector3 gravity_vec = handle->dynamicsWorld->getGravity();
00079 gravity[0] = gravity_vec.x() * bulletWorldScalingFactor;
00080 gravity[1] = gravity_vec.y() * bulletWorldScalingFactor;
00081 gravity[2] = gravity_vec.z() * bulletWorldScalingFactor;
00082 }
00083
00084 void setGravity(DynamicsWorldHandle *handle, double *gravity)
00085 {
00086 handle->dynamicsWorld->setGravity(
00087 btVector3(gravity[0] * bulletWorldScalingFactor, gravity[1] * bulletWorldScalingFactor, gravity[2] * bulletWorldScalingFactor));
00088 }
00089
00090 void stepSimulation(DynamicsWorldHandle *handle, double timeStep)
00091 {
00092 handle->dynamicsWorld->stepSimulation(timeStep);
00093 }
00094
00095 void addConstraint(DynamicsWorldHandle *handle, btTypedConstraint *constraint, bool disableCollisions)
00096 {
00097 handle->dynamicsWorld->addConstraint(constraint, disableCollisions);
00098 }
00099
00100 void removeConstraint(DynamicsWorldHandle *handle, btTypedConstraint *constraint)
00101 {
00102 handle->dynamicsWorld->removeConstraint(constraint);
00103 }
00104
00105 int getNumConstraints(DynamicsWorldHandle *handle)
00106 {
00107 return handle->dynamicsWorld->getNumConstraints();
00108 }
00109
00110 btTypedConstraint *getConstraint(DynamicsWorldHandle *handle, int index)
00111 {
00112 return handle->dynamicsWorld->getConstraint(index);
00113 }
00114
00115 void addRigidBody(DynamicsWorldHandle *handle, btRigidBody *body)
00116 {
00117 handle->dynamicsWorld->addRigidBody(body);
00118 }
00119
00120 void addRigidBodyWithMask(DynamicsWorldHandle *handle, btRigidBody *body, short group, short mask)
00121 {
00122 btDiscreteDynamicsWorld *world = dynamic_cast<btDiscreteDynamicsWorld *>(handle->dynamicsWorld);
00123
00124 if(world)
00125 world->addRigidBody(body, group, mask);
00126 else
00127 addRigidBody(handle, body);
00128 }
00129
00130 void removeRigidBody(DynamicsWorldHandle *handle, btRigidBody *body)
00131 {
00132 handle->dynamicsWorld->removeRigidBody(body);
00133 }
00134
00135 int getNumRigidBodies(const DynamicsWorldHandle *handle)
00136 {
00137 return handle->dynamicsWorld->getNumCollisionObjects();
00138 }
00139
00140 btRigidBody *getRigidBody(const DynamicsWorldHandle *handle, int index)
00141 {
00142 return btRigidBody::upcast(handle->dynamicsWorld->getCollisionObjectArray()[index]);
00143 }
00144
00145 void setDebugDrawer(DynamicsWorldHandle *handle, btIDebugDraw *debugDrawer)
00146 {
00147 btDiscreteDynamicsWorld *handle_ =
00148 dynamic_cast<btDiscreteDynamicsWorld *>(handle->dynamicsWorld);
00149
00150 if(handle_)
00151 handle_->setDebugDrawer(debugDrawer);
00152 }
00153
00154 btIDebugDraw *getDebugDrawer(DynamicsWorldHandle *handle)
00155 {
00156 btDiscreteDynamicsWorld *handle_ =
00157 dynamic_cast<btDiscreteDynamicsWorld *>(handle->dynamicsWorld);
00158
00159 if(handle_)
00160 return handle_->getDebugDrawer();
00161 else
00162 return NULL;
00163 }
00164
00165 void debugDrawWorld(DynamicsWorldHandle *handle)
00166 {
00167 btDiscreteDynamicsWorld *handle_ =
00168 dynamic_cast<btDiscreteDynamicsWorld *>(handle->dynamicsWorld);
00169
00170 if(handle_)
00171 handle_->debugDrawWorld();
00172 }
00173
00174 void serializeWorld(DynamicsWorldHandle *handle, btSerializer *serializer)
00175 {
00176 handle->dynamicsWorld->serialize(serializer);
00177 }
00178
00181 void performDiscreteCollisionDetection(DynamicsWorldHandle *handle)
00182 {
00183 handle->dynamicsWorld->performDiscreteCollisionDetection();
00184 }
00185
00186 int getNumManifolds(DynamicsWorldHandle *handle)
00187 {
00188 return handle->dispatcher->getNumManifolds();
00189 }
00190
00191 btPersistentManifold *getManifoldByIndex(DynamicsWorldHandle *handle, int index)
00192 {
00193 return handle->dispatcher->getManifoldByIndexInternal(index);
00194 }
00195
00196 const btCollisionObject *manifoldGetBody0(btPersistentManifold *manifold)
00197 {
00198 return reinterpret_cast<const btCollisionObject *>(manifold->getBody0());
00199 }
00200
00201 const btCollisionObject *manifoldGetBody1(btPersistentManifold *manifold)
00202 {
00203 return reinterpret_cast<const btCollisionObject *>(manifold->getBody1());
00204 }
00205
00206 int manifoldGetNumContactPoints(btPersistentManifold *manifold)
00207 {
00208 return manifold->getNumContacts();
00209 }
00210
00211 void manifoldGetContactPoint0(btPersistentManifold *manifold, int index, double *point)
00212 {
00213 btManifoldPoint &pt = manifold->getContactPoint(index);
00214
00215 const btVector3 &point_on_a_vec = pt.getPositionWorldOnA();
00216 point[0] = point_on_a_vec.x() / bulletWorldScalingFactor;
00217 point[1] = point_on_a_vec.y() / bulletWorldScalingFactor;
00218 point[2] = point_on_a_vec.z() / bulletWorldScalingFactor;
00219 }
00220
00221 void manifoldGetContactPoint1(btPersistentManifold *manifold, int index, double *point)
00222 {
00223 btManifoldPoint &pt = manifold->getContactPoint(index);
00224
00225 const btVector3 &point_on_b_vec = pt.getPositionWorldOnB();
00226 point[0] = point_on_b_vec.x() / bulletWorldScalingFactor;
00227 point[1] = point_on_b_vec.y() / bulletWorldScalingFactor;
00228 point[2] = point_on_b_vec.z() / bulletWorldScalingFactor;
00229 }
00230
00231 }