rigid_body.cpp
Go to the documentation of this file.
00001 
00031 #include <btBulletDynamicsCommon.h>
00032 
00033 extern double bulletWorldScalingFactor;
00034 
00035 extern "C"
00036 {
00037 
00038   btRigidBody *newRigidBody(double mass, btMotionState *motionState, btCollisionShape *collisionShape)
00039   {
00040     btVector3 intertia(0, 0, 0);
00041     collisionShape->calculateLocalInertia(mass, intertia);
00042     return new btRigidBody(mass, motionState, collisionShape, intertia);
00043   }
00044 
00045   void deleteRigidBody(btRigidBody *body)
00046   {
00047     delete body;
00048   }
00049 
00050   void getTotalForce(btRigidBody *body, double *forceVector)
00051   {
00052     btVector3 forceVectorBt = body->getTotalForce() / bulletWorldScalingFactor;
00053     forceVector[0] = forceVectorBt.x();
00054     forceVector[1] = forceVectorBt.y();
00055     forceVector[2] = forceVectorBt.z();
00056   }
00057 
00058   void getTotalTorque(btRigidBody *body, double *torqueVector)
00059   {
00060     btVector3 torqueVectorBt = body->getTotalTorque();
00061     torqueVector[0] = torqueVectorBt.x();
00062     torqueVector[1] = torqueVectorBt.y();
00063     torqueVector[2] = torqueVectorBt.z();
00064   }
00065 
00066   void applyForce(btRigidBody *body, double *force, double *rel_pos)
00067   {
00068     btVector3 force_vec = btVector3(force[0], force[1], force[2]) * bulletWorldScalingFactor;
00069     btVector3 rel_pos_vec = btVector3(rel_pos[0], rel_pos[1], rel_pos[2]) * bulletWorldScalingFactor;
00070     body->applyForce(force_vec, rel_pos_vec);
00071   }
00072 
00073   void applyCentralForce(btRigidBody *body, double *force)
00074   {
00075     btVector3 force_vec = btVector3(force[0], force[1], force[2]) * bulletWorldScalingFactor;
00076     body->applyCentralForce(force_vec);
00077   }
00078 
00079   void applyTorque(btRigidBody *body, double *torque)
00080   {
00081     btVector3 torque_vec(torque[0], torque[1], torque[2]);
00082     body->applyTorque(torque_vec);
00083   }
00084 
00085   void clearForces(btRigidBody *body)
00086   {
00087     body->clearForces();
00088   }
00089 
00090   void getLinearVelocity(btRigidBody *body, double *velocity)
00091   {
00092     const btVector3 &vel = body->getLinearVelocity() / bulletWorldScalingFactor;
00093     velocity[0] = vel.x();
00094     velocity[1] = vel.y();
00095     velocity[2] = vel.z();
00096   }
00097 
00098   void setLinearVelocity(btRigidBody *body, double *velocity)
00099   {
00100     body->setLinearVelocity(
00101       btVector3(velocity[0] * bulletWorldScalingFactor,
00102         velocity[1] * bulletWorldScalingFactor,
00103         velocity[2] * bulletWorldScalingFactor));
00104   }
00105 
00106   void getAngularVelocity(btRigidBody *body, double *velocity)
00107   {
00108     const btVector3 &vel = body->getAngularVelocity();
00109     velocity[0] = vel.x();
00110     velocity[1] = vel.y();
00111     velocity[2] = vel.z();
00112   }
00113 
00114   void setAngularVelocity(btRigidBody *body, double *velocity)
00115   {
00116     body->setAngularVelocity(
00117       btVector3(velocity[0], velocity[1], velocity[2]));
00118   }
00119   
00120   btMotionState *getMotionState(btRigidBody *body)
00121   {
00122     return body->getMotionState();
00123   }
00124 
00125   void setMotionState(btRigidBody *body, btMotionState *motionState)
00126   {
00127     body->setMotionState(motionState);
00128   }
00129 
00130   void setActivationState(btRigidBody *body, int newState)
00131   {
00132     body->setActivationState(newState);
00133   }
00134 
00135   int getActivationState(btRigidBody *body)
00136   {
00137     return body->getActivationState();
00138   }
00139 
00140   void setCollisionFlags(btRigidBody *body, int flags)
00141   {
00142     body->setCollisionFlags(flags);
00143   }
00144 
00145   int getCollisionFlags(btRigidBody *body)
00146   {
00147     return body->getCollisionFlags();
00148   }
00149 
00150   btCollisionShape *getCollisionShape(btRigidBody *body)
00151   {
00152     return body->getCollisionShape();
00153   }
00154 
00155   void getAabb(btRigidBody *body, double *aabbMin, double *aabbMax)
00156   {
00157     btVector3 min;
00158     btVector3 max;
00159 
00160     body->getAabb(min, max);
00161     aabbMin[0] = min.x() / bulletWorldScalingFactor;
00162     aabbMin[1] = min.y() / bulletWorldScalingFactor;
00163     aabbMin[2] = min.z() / bulletWorldScalingFactor;
00164     aabbMax[0] = max.x() / bulletWorldScalingFactor;
00165     aabbMax[1] = max.y() / bulletWorldScalingFactor;
00166     aabbMax[2] = max.z() / bulletWorldScalingFactor;
00167   }
00168 
00169   void getCollisionFilter(btRigidBody *body, int *group, int *mask)
00170   {
00171     *group = body->getBroadphaseProxy()->m_collisionFilterGroup;
00172     *mask =  body->getBroadphaseProxy()->m_collisionFilterMask;
00173   }
00174 
00175   void setCollisionFilter(btRigidBody *body, int group, int mask)
00176   {
00177     body->getBroadphaseProxy()->m_collisionFilterGroup = group;
00178     body->getBroadphaseProxy()->m_collisionFilterMask = mask;
00179   }
00180 
00181   void setMassProps(btRigidBody *body, double mass)
00182   {
00183     btVector3 inverseInertia = body->getInvInertiaDiagLocal();
00184     btVector3 inertia = btVector3(
00185         inverseInertia.x() != 0.0 ? 1.0 / inverseInertia.x() : 0.0,
00186         inverseInertia.y() != 0.0 ? 1.0 / inverseInertia.y() : 0.0,
00187         inverseInertia.z() != 0.0 ? 1.0 / inverseInertia.z() : 0.0);
00188     body->setMassProps(mass, inertia);
00189   }
00190 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


cl_bullet
Author(s): Lorenz Moesenlechner
autogenerated on Thu May 23 2013 05:47:18