MultiDofDemo.cpp 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448
  1. #include "MultiDofDemo.h"
  2. #include "../OpenGLWindow/SimpleOpenGL3App.h"
  3. #include "btBulletDynamicsCommon.h"
  4. #include "BulletDynamics/Featherstone/btMultiBody.h"
  5. #include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
  6. #include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
  7. #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
  8. #include "BulletDynamics/Featherstone/btMultiBodyLink.h"
  9. #include "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h"
  10. #include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
  11. #include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
  12. #include "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h"
  13. #include "BulletDynamics/Featherstone/btMultiBodySliderConstraint.h"
  14. #include "../OpenGLWindow/GLInstancingRenderer.h"
  15. #include "BulletCollision/CollisionShapes/btShapeHull.h"
  16. #include "../CommonInterfaces/CommonMultiBodyBase.h"
  17. class MultiDofDemo : public CommonMultiBodyBase
  18. {
  19. public:
  20. MultiDofDemo(GUIHelperInterface* helper);
  21. virtual ~MultiDofDemo();
  22. virtual void initPhysics();
  23. virtual void stepSimulation(float deltaTime);
  24. virtual void resetCamera()
  25. {
  26. float dist = 1;
  27. float pitch = 50;
  28. float yaw = 35;
  29. float targetPos[3]={-3,2.8,-2.5};
  30. m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
  31. }
  32. btMultiBody* createFeatherstoneMultiBody_testMultiDof(class btMultiBodyDynamicsWorld* world, int numLinks, const btVector3& basePosition, const btVector3 &baseHalfExtents, const btVector3 &linkHalfExtents, bool spherical = false, bool floating = false);
  33. void addColliders_testMultiDof(btMultiBody *pMultiBody, btMultiBodyDynamicsWorld *pWorld, const btVector3 &baseHalfExtents, const btVector3 &linkHalfExtents);
  34. void addBoxes_testMultiDof();
  35. };
  36. static bool g_floatingBase = false;
  37. static bool g_firstInit = true;
  38. static float scaling = 0.4f;
  39. static float friction = 1.;
  40. #define ARRAY_SIZE_X 5
  41. #define ARRAY_SIZE_Y 5
  42. #define ARRAY_SIZE_Z 5
  43. //maximum number of objects (and allow user to shoot additional boxes)
  44. #define MAX_PROXIES (ARRAY_SIZE_X*ARRAY_SIZE_Y*ARRAY_SIZE_Z + 1024)
  45. #define START_POS_X -5
  46. //#define START_POS_Y 12
  47. #define START_POS_Y 2
  48. #define START_POS_Z -3
  49. MultiDofDemo::MultiDofDemo(GUIHelperInterface* helper)
  50. :CommonMultiBodyBase(helper)
  51. {
  52. m_guiHelper->setUpAxis(1);
  53. }
  54. MultiDofDemo::~MultiDofDemo()
  55. {
  56. }
  57. void MultiDofDemo::stepSimulation(float deltaTime)
  58. {
  59. //use a smaller internal timestep, there are stability issues
  60. float internalTimeStep = 1./240.f;
  61. m_dynamicsWorld->stepSimulation(deltaTime,10,internalTimeStep);
  62. }
  63. void MultiDofDemo::initPhysics()
  64. {
  65. m_guiHelper->setUpAxis(1);
  66. if(g_firstInit)
  67. {
  68. m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraDistance(btScalar(10.*scaling));
  69. m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraPitch(50);
  70. g_firstInit = false;
  71. }
  72. ///collision configuration contains default setup for memory, collision setup
  73. m_collisionConfiguration = new btDefaultCollisionConfiguration();
  74. ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
  75. m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
  76. m_broadphase = new btDbvtBroadphase();
  77. //Use the btMultiBodyConstraintSolver for Featherstone btMultiBody support
  78. btMultiBodyConstraintSolver* sol = new btMultiBodyConstraintSolver;
  79. m_solver = sol;
  80. //use btMultiBodyDynamicsWorld for Featherstone btMultiBody support
  81. btMultiBodyDynamicsWorld* world = new btMultiBodyDynamicsWorld(m_dispatcher,m_broadphase,sol,m_collisionConfiguration);
  82. m_dynamicsWorld = world;
  83. // m_dynamicsWorld->setDebugDrawer(&gDebugDraw);
  84. m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
  85. m_dynamicsWorld->setGravity(btVector3(0,-10,0));
  86. ///create a few basic rigid bodies
  87. btVector3 groundHalfExtents(50,50,50);
  88. btCollisionShape* groundShape = new btBoxShape(groundHalfExtents);
  89. //groundShape->initializePolyhedralFeatures();
  90. // btCollisionShape* groundShape = new btStaticPlaneShape(btVector3(0,1,0),50);
  91. m_collisionShapes.push_back(groundShape);
  92. btTransform groundTransform;
  93. groundTransform.setIdentity();
  94. groundTransform.setOrigin(btVector3(0,-50,00));
  95. /////////////////////////////////////////////////////////////////
  96. /////////////////////////////////////////////////////////////////
  97. bool damping = true;
  98. bool gyro = true;
  99. int numLinks = 5;
  100. bool spherical = true; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals
  101. bool multibodyOnly = false;
  102. bool canSleep = true;
  103. bool selfCollide = false;
  104. bool multibodyConstraint = true;
  105. btVector3 linkHalfExtents(0.05, 0.37, 0.1);
  106. btVector3 baseHalfExtents(0.05, 0.37, 0.1);
  107. btMultiBody* mbC = createFeatherstoneMultiBody_testMultiDof(world, numLinks, btVector3(-0.4f, 3.f, 0.f), linkHalfExtents, baseHalfExtents, spherical, g_floatingBase);
  108. //mbC->forceMultiDof(); //if !spherical, you can comment this line to check the 1DoF algorithm
  109. g_floatingBase = ! g_floatingBase;
  110. mbC->setCanSleep(canSleep);
  111. mbC->setHasSelfCollision(selfCollide);
  112. mbC->setUseGyroTerm(gyro);
  113. //
  114. if(!damping)
  115. {
  116. mbC->setLinearDamping(0.f);
  117. mbC->setAngularDamping(0.f);
  118. }else
  119. { mbC->setLinearDamping(0.1f);
  120. mbC->setAngularDamping(0.9f);
  121. }
  122. //
  123. m_dynamicsWorld->setGravity(btVector3(0, -9.81 ,0));
  124. //////////////////////////////////////////////
  125. if(numLinks > 0)
  126. {
  127. btScalar q0 = 45.f * SIMD_PI/ 180.f;
  128. if(!spherical)
  129. {
  130. mbC->setJointPosMultiDof(0, &q0);
  131. }
  132. else
  133. {
  134. btQuaternion quat0(btVector3(1, 1, 0).normalized(), q0);
  135. quat0.normalize();
  136. mbC->setJointPosMultiDof(0, quat0);
  137. }
  138. }
  139. ///
  140. addColliders_testMultiDof(mbC, world, baseHalfExtents, linkHalfExtents);
  141. /////////////////////////////////////////////////////////////////
  142. btScalar groundHeight = -51.55;
  143. if (!multibodyOnly)
  144. {
  145. btScalar mass(0.);
  146. //rigidbody is dynamic if and only if mass is non zero, otherwise static
  147. bool isDynamic = (mass != 0.f);
  148. btVector3 localInertia(0,0,0);
  149. if (isDynamic)
  150. groundShape->calculateLocalInertia(mass,localInertia);
  151. //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
  152. groundTransform.setIdentity();
  153. groundTransform.setOrigin(btVector3(0,groundHeight,0));
  154. btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
  155. btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,groundShape,localInertia);
  156. btRigidBody* body = new btRigidBody(rbInfo);
  157. //add the body to the dynamics world
  158. m_dynamicsWorld->addRigidBody(body,1,1+2);//,1,1+2);
  159. }
  160. /////////////////////////////////////////////////////////////////
  161. if(!multibodyOnly)
  162. {
  163. btVector3 halfExtents(.5,.5,.5);
  164. btBoxShape* colShape = new btBoxShape(halfExtents);
  165. //btCollisionShape* colShape = new btSphereShape(btScalar(1.));
  166. m_collisionShapes.push_back(colShape);
  167. /// Create Dynamic Objects
  168. btTransform startTransform;
  169. startTransform.setIdentity();
  170. btScalar mass(1.f);
  171. //rigidbody is dynamic if and only if mass is non zero, otherwise static
  172. bool isDynamic = (mass != 0.f);
  173. btVector3 localInertia(0,0,0);
  174. if (isDynamic)
  175. colShape->calculateLocalInertia(mass,localInertia);
  176. startTransform.setOrigin(btVector3(
  177. btScalar(0.0),
  178. 0.0,
  179. btScalar(0.0)));
  180. //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
  181. btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
  182. btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,colShape,localInertia);
  183. btRigidBody* body = new btRigidBody(rbInfo);
  184. m_dynamicsWorld->addRigidBody(body);//,1,1+2);
  185. if (multibodyConstraint) {
  186. btVector3 pointInA = -linkHalfExtents;
  187. btVector3 pointInB = halfExtents;
  188. btMatrix3x3 frameInA;
  189. btMatrix3x3 frameInB;
  190. frameInA.setIdentity();
  191. frameInB.setIdentity();
  192. btVector3 jointAxis(1.0,0.0,0.0);
  193. btMultiBodySliderConstraint* p2p = new btMultiBodySliderConstraint(mbC,numLinks-1,body,pointInA,pointInB,frameInA,frameInB,jointAxis);
  194. //btMultiBodyFixedConstraint* p2p = new btMultiBodyFixedConstraint(mbC,numLinks-1,mbC,numLinks-4,pointInA,pointInA,frameInA,frameInB);
  195. p2p->setMaxAppliedImpulse(2.0);
  196. m_dynamicsWorld->addMultiBodyConstraint(p2p);
  197. }
  198. }
  199. m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
  200. /////////////////////////////////////////////////////////////////
  201. }
  202. btMultiBody* MultiDofDemo::createFeatherstoneMultiBody_testMultiDof(btMultiBodyDynamicsWorld *pWorld, int numLinks, const btVector3 &basePosition, const btVector3 &baseHalfExtents, const btVector3 &linkHalfExtents, bool spherical, bool floating)
  203. {
  204. //init the base
  205. btVector3 baseInertiaDiag(0.f, 0.f, 0.f);
  206. float baseMass = 1.f;
  207. if(baseMass)
  208. {
  209. btCollisionShape *pTempBox = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2]));
  210. pTempBox->calculateLocalInertia(baseMass, baseInertiaDiag);
  211. delete pTempBox;
  212. }
  213. bool canSleep = false;
  214. btMultiBody *pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, !floating, canSleep);
  215. btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f);
  216. pMultiBody->setBasePos(basePosition);
  217. pMultiBody->setWorldToBaseRot(baseOriQuat);
  218. btVector3 vel(0, 0, 0);
  219. // pMultiBody->setBaseVel(vel);
  220. //init the links
  221. btVector3 hingeJointAxis(1, 0, 0);
  222. float linkMass = 1.f;
  223. btVector3 linkInertiaDiag(0.f, 0.f, 0.f);
  224. btCollisionShape *pTempBox = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2]));
  225. pTempBox->calculateLocalInertia(linkMass, linkInertiaDiag);
  226. delete pTempBox;
  227. //y-axis assumed up
  228. btVector3 parentComToCurrentCom(0, -linkHalfExtents[1] * 2.f, 0); //par body's COM to cur body's COM offset
  229. btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1], 0); //cur body's COM to cur body's PIV offset
  230. btVector3 parentComToCurrentPivot = parentComToCurrentCom - currentPivotToCurrentCom; //par body's COM to cur body's PIV offset
  231. //////
  232. btScalar q0 = 0.f * SIMD_PI/ 180.f;
  233. btQuaternion quat0(btVector3(0, 1, 0).normalized(), q0);
  234. quat0.normalize();
  235. /////
  236. for(int i = 0; i < numLinks; ++i)
  237. {
  238. if(!spherical)
  239. pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot, currentPivotToCurrentCom, false);
  240. else
  241. //pMultiBody->setupPlanar(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f)/*quat0*/, btVector3(1, 0, 0), parentComToCurrentPivot*2, false);
  242. pMultiBody->setupSpherical(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), parentComToCurrentPivot, currentPivotToCurrentCom, false);
  243. }
  244. pMultiBody->finalizeMultiDof();
  245. ///
  246. pWorld->addMultiBody(pMultiBody);
  247. ///
  248. return pMultiBody;
  249. }
  250. void MultiDofDemo::addColliders_testMultiDof(btMultiBody *pMultiBody, btMultiBodyDynamicsWorld *pWorld, const btVector3 &baseHalfExtents, const btVector3 &linkHalfExtents)
  251. {
  252. btAlignedObjectArray<btQuaternion> world_to_local;
  253. world_to_local.resize(pMultiBody->getNumLinks() + 1);
  254. btAlignedObjectArray<btVector3> local_origin;
  255. local_origin.resize(pMultiBody->getNumLinks() + 1);
  256. world_to_local[0] = pMultiBody->getWorldToBaseRot();
  257. local_origin[0] = pMultiBody->getBasePos();
  258. {
  259. // float pos[4]={local_origin[0].x(),local_origin[0].y(),local_origin[0].z(),1};
  260. btScalar quat[4]={-world_to_local[0].x(),-world_to_local[0].y(),-world_to_local[0].z(),world_to_local[0].w()};
  261. if (1)
  262. {
  263. btCollisionShape* box = new btBoxShape(baseHalfExtents);
  264. btMultiBodyLinkCollider* col= new btMultiBodyLinkCollider(pMultiBody, -1);
  265. col->setCollisionShape(box);
  266. btTransform tr;
  267. tr.setIdentity();
  268. tr.setOrigin(local_origin[0]);
  269. tr.setRotation(btQuaternion(quat[0],quat[1],quat[2],quat[3]));
  270. col->setWorldTransform(tr);
  271. pWorld->addCollisionObject(col, 2,1+2);
  272. col->setFriction(friction);
  273. pMultiBody->setBaseCollider(col);
  274. }
  275. }
  276. for (int i=0; i < pMultiBody->getNumLinks(); ++i)
  277. {
  278. const int parent = pMultiBody->getParent(i);
  279. world_to_local[i+1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent+1];
  280. local_origin[i+1] = local_origin[parent+1] + (quatRotate(world_to_local[i+1].inverse() , pMultiBody->getRVector(i)));
  281. }
  282. for (int i=0; i < pMultiBody->getNumLinks(); ++i)
  283. {
  284. btVector3 posr = local_origin[i+1];
  285. // float pos[4]={posr.x(),posr.y(),posr.z(),1};
  286. btScalar quat[4]={-world_to_local[i+1].x(),-world_to_local[i+1].y(),-world_to_local[i+1].z(),world_to_local[i+1].w()};
  287. btCollisionShape* box = new btBoxShape(linkHalfExtents);
  288. btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i);
  289. col->setCollisionShape(box);
  290. btTransform tr;
  291. tr.setIdentity();
  292. tr.setOrigin(posr);
  293. tr.setRotation(btQuaternion(quat[0],quat[1],quat[2],quat[3]));
  294. col->setWorldTransform(tr);
  295. col->setFriction(friction);
  296. pWorld->addCollisionObject(col,2,1+2);
  297. pMultiBody->getLink(i).m_collider=col;
  298. }
  299. }
  300. void MultiDofDemo::addBoxes_testMultiDof()
  301. {
  302. //create a few dynamic rigidbodies
  303. // Re-using the same collision is better for memory usage and performance
  304. btBoxShape* colShape = new btBoxShape(btVector3(1,1,1));
  305. //btCollisionShape* colShape = new btSphereShape(btScalar(1.));
  306. m_collisionShapes.push_back(colShape);
  307. /// Create Dynamic Objects
  308. btTransform startTransform;
  309. startTransform.setIdentity();
  310. btScalar mass(1.f);
  311. //rigidbody is dynamic if and only if mass is non zero, otherwise static
  312. bool isDynamic = (mass != 0.f);
  313. btVector3 localInertia(0,0,0);
  314. if (isDynamic)
  315. colShape->calculateLocalInertia(mass,localInertia);
  316. float start_x = START_POS_X - ARRAY_SIZE_X/2;
  317. float start_y = START_POS_Y;
  318. float start_z = START_POS_Z - ARRAY_SIZE_Z/2;
  319. for (int k=0;k<ARRAY_SIZE_Y;k++)
  320. {
  321. for (int i=0;i<ARRAY_SIZE_X;i++)
  322. {
  323. for(int j = 0;j<ARRAY_SIZE_Z;j++)
  324. {
  325. startTransform.setOrigin(btVector3(
  326. btScalar(3.0*i + start_x),
  327. btScalar(3.0*k + start_y),
  328. btScalar(3.0*j + start_z)));
  329. //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
  330. btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
  331. btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,colShape,localInertia);
  332. btRigidBody* body = new btRigidBody(rbInfo);
  333. m_dynamicsWorld->addRigidBody(body);//,1,1+2);
  334. }
  335. }
  336. }
  337. }
  338. class CommonExampleInterface* MultiDofCreateFunc(struct CommonExampleOptions& options)
  339. {
  340. return new MultiDofDemo(options.m_guiHelper);
  341. }