btParallelConstraintSolver.cpp 50 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552
  1. /*
  2. Copyright (C) 2010 Sony Computer Entertainment Inc.
  3. All rights reserved.
  4. This software is provided 'as-is', without any express or implied warranty.
  5. In no event will the authors be held liable for any damages arising from the use of this software.
  6. Permission is granted to anyone to use this software for any purpose,
  7. including commercial applications, and to alter it and redistribute it freely,
  8. subject to the following restrictions:
  9. 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
  10. 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
  11. 3. This notice may not be removed or altered from any source distribution.
  12. */
  13. #include "btParallelConstraintSolver.h"
  14. #include "bullet/BulletDynamics/ConstraintSolver/btContactSolverInfo.h"
  15. #include "bullet/BulletCollision//BroadphaseCollision/btDispatcher.h"
  16. #include "bullet/LinearMath/btPoolAllocator.h"
  17. #include "bullet/BulletCollision//NarrowPhaseCollision/btPersistentManifold.h"
  18. #include "bullet/BulletMultiThreaded/vectormath2bullet.h"
  19. #include "bullet/LinearMath/btQuickprof.h"
  20. #include "bullet/BulletMultiThreaded/btThreadSupportInterface.h"
  21. #ifdef PFX_USE_FREE_VECTORMATH
  22. #include "vecmath/vmInclude.h"
  23. #else
  24. #include "bullet/vectormath/vmInclude.h"
  25. #endif //PFX_USE_FREE_VECTORMATH
  26. #include "HeapManager.h"
  27. #include "PlatformDefinitions.h"
  28. //#include "PfxSimdUtils.h"
  29. #include "bullet/LinearMath/btScalar.h"
  30. #include "TrbStateVec.h"
  31. /////////////////
  32. #define TMP_BUFF_BYTES (15*1024*1024)
  33. unsigned char ATTRIBUTE_ALIGNED128(tmp_buff[TMP_BUFF_BYTES]);
  34. // Project Gauss Seidel or the equivalent Sequential Impulse
  35. inline void resolveSingleConstraintRowGeneric(PfxSolverBody& body1,PfxSolverBody& body2,const btSolverConstraint& c)
  36. {
  37. btScalar deltaImpulse = c.m_rhs-btScalar(c.m_appliedImpulse)*c.m_cfm;
  38. const btScalar deltaVel1Dotn = c.m_contactNormal1.dot(getBtVector3(body1.mDeltaLinearVelocity)) + c.m_relpos1CrossNormal.dot(getBtVector3(body1.mDeltaAngularVelocity));
  39. const btScalar deltaVel2Dotn = c.m_contactNormal2.dot(getBtVector3(body2.mDeltaLinearVelocity)) + c.m_relpos2CrossNormal.dot(getBtVector3(body2.mDeltaAngularVelocity));
  40. // const btScalar delta_rel_vel = deltaVel1Dotn-deltaVel2Dotn;
  41. deltaImpulse -= deltaVel1Dotn*c.m_jacDiagABInv;
  42. deltaImpulse -= deltaVel2Dotn*c.m_jacDiagABInv;
  43. const btScalar sum = btScalar(c.m_appliedImpulse) + deltaImpulse;
  44. if (sum < c.m_lowerLimit)
  45. {
  46. deltaImpulse = c.m_lowerLimit-c.m_appliedImpulse;
  47. c.m_appliedImpulse = c.m_lowerLimit;
  48. }
  49. else if (sum > c.m_upperLimit)
  50. {
  51. deltaImpulse = c.m_upperLimit-c.m_appliedImpulse;
  52. c.m_appliedImpulse = c.m_upperLimit;
  53. }
  54. else
  55. {
  56. c.m_appliedImpulse = sum;
  57. }
  58. if (body1.mMassInv)
  59. {
  60. btVector3 linearComponent = c.m_contactNormal1*body1.mMassInv;
  61. body1.mDeltaLinearVelocity += vmVector3(linearComponent.getX()*deltaImpulse,linearComponent.getY()*deltaImpulse,linearComponent.getZ()*deltaImpulse);
  62. btVector3 tmp=c.m_angularComponentA*(btVector3(deltaImpulse,deltaImpulse,deltaImpulse));
  63. body1.mDeltaAngularVelocity += vmVector3(tmp.getX(),tmp.getY(),tmp.getZ());
  64. }
  65. if (body2.mMassInv)
  66. {
  67. btVector3 linearComponent = c.m_contactNormal2*body2.mMassInv;
  68. body2.mDeltaLinearVelocity += vmVector3(linearComponent.getX()*deltaImpulse,linearComponent.getY()*deltaImpulse,linearComponent.getZ()*deltaImpulse);
  69. btVector3 tmp = c.m_angularComponentB*((btVector3(deltaImpulse,deltaImpulse,deltaImpulse)));//*m_angularFactor);
  70. body2.mDeltaAngularVelocity += vmVector3(tmp.getX(),tmp.getY(),tmp.getZ());
  71. }
  72. //body1.internalApplyImpulse(c.m_contactNormal1*body1.internalGetInvMass(),c.m_angularComponentA,deltaImpulse);
  73. //body2.internalApplyImpulse(c.m_contactNormal2*body2.internalGetInvMass(),c.m_angularComponentB,deltaImpulse);
  74. }
  75. static SIMD_FORCE_INLINE
  76. void pfxSolveLinearConstraintRow(btConstraintRow &constraint,
  77. vmVector3 &deltaLinearVelocityA,vmVector3 &deltaAngularVelocityA,
  78. float massInvA,const vmMatrix3 &inertiaInvA,const vmVector3 &rA,
  79. vmVector3 &deltaLinearVelocityB,vmVector3 &deltaAngularVelocityB,
  80. float massInvB,const vmMatrix3 &inertiaInvB,const vmVector3 &rB)
  81. {
  82. const vmVector3 normal(btReadVector3(constraint.m_normal));
  83. btScalar deltaImpulse = constraint.m_rhs;
  84. vmVector3 dVA = deltaLinearVelocityA + cross(deltaAngularVelocityA,rA);
  85. vmVector3 dVB = deltaLinearVelocityB + cross(deltaAngularVelocityB,rB);
  86. deltaImpulse -= constraint.m_jacDiagInv * dot(normal,dVA-dVB);
  87. btScalar oldImpulse = constraint.m_accumImpulse;
  88. constraint.m_accumImpulse = btClamped(oldImpulse + deltaImpulse,constraint.m_lowerLimit,constraint.m_upperLimit);
  89. deltaImpulse = constraint.m_accumImpulse - oldImpulse;
  90. deltaLinearVelocityA += deltaImpulse * massInvA * normal;
  91. deltaAngularVelocityA += deltaImpulse * inertiaInvA * cross(rA,normal);
  92. deltaLinearVelocityB -= deltaImpulse * massInvB * normal;
  93. deltaAngularVelocityB -= deltaImpulse * inertiaInvB * cross(rB,normal);
  94. }
  95. void btSolveContactConstraint(
  96. btConstraintRow &constraintResponse,
  97. btConstraintRow &constraintFriction1,
  98. btConstraintRow &constraintFriction2,
  99. const vmVector3 &contactPointA,
  100. const vmVector3 &contactPointB,
  101. PfxSolverBody &solverBodyA,
  102. PfxSolverBody &solverBodyB,
  103. float friction
  104. )
  105. {
  106. vmVector3 rA = rotate(solverBodyA.mOrientation,contactPointA);
  107. vmVector3 rB = rotate(solverBodyB.mOrientation,contactPointB);
  108. pfxSolveLinearConstraintRow(constraintResponse,
  109. solverBodyA.mDeltaLinearVelocity,solverBodyA.mDeltaAngularVelocity,solverBodyA.mMassInv,solverBodyA.mInertiaInv,rA,
  110. solverBodyB.mDeltaLinearVelocity,solverBodyB.mDeltaAngularVelocity,solverBodyB.mMassInv,solverBodyB.mInertiaInv,rB);
  111. float mf = friction*fabsf(constraintResponse.m_accumImpulse);
  112. constraintFriction1.m_lowerLimit = -mf;
  113. constraintFriction1.m_upperLimit = mf;
  114. constraintFriction2.m_lowerLimit = -mf;
  115. constraintFriction2.m_upperLimit = mf;
  116. pfxSolveLinearConstraintRow(constraintFriction1,
  117. solverBodyA.mDeltaLinearVelocity,solverBodyA.mDeltaAngularVelocity,solverBodyA.mMassInv,solverBodyA.mInertiaInv,rA,
  118. solverBodyB.mDeltaLinearVelocity,solverBodyB.mDeltaAngularVelocity,solverBodyB.mMassInv,solverBodyB.mInertiaInv,rB);
  119. pfxSolveLinearConstraintRow(constraintFriction2,
  120. solverBodyA.mDeltaLinearVelocity,solverBodyA.mDeltaAngularVelocity,solverBodyA.mMassInv,solverBodyA.mInertiaInv,rA,
  121. solverBodyB.mDeltaLinearVelocity,solverBodyB.mDeltaAngularVelocity,solverBodyB.mMassInv,solverBodyB.mInertiaInv,rB);
  122. }
  123. void CustomSolveConstraintsTaskParallel(
  124. const PfxParallelGroup *contactParallelGroup,const PfxParallelBatch *contactParallelBatches,
  125. PfxConstraintPair *contactPairs,uint32_t numContactPairs,
  126. btPersistentManifold* offsetContactManifolds,
  127. btConstraintRow* offsetContactConstraintRows,
  128. const PfxParallelGroup *jointParallelGroup,const PfxParallelBatch *jointParallelBatches,
  129. PfxConstraintPair *jointPairs,uint32_t numJointPairs,
  130. btSolverConstraint* offsetSolverConstraints,
  131. TrbState *offsetRigStates,
  132. PfxSolverBody *offsetSolverBodies,
  133. uint32_t numRigidBodies,
  134. int iteration,unsigned int taskId,unsigned int numTasks,btBarrier *barrier)
  135. {
  136. PfxSolverBody staticBody;
  137. staticBody.mMassInv = 0.f;
  138. staticBody.mDeltaAngularVelocity=vmVector3(0,0,0);
  139. staticBody.mDeltaLinearVelocity =vmVector3(0,0,0);
  140. for(int k=0;k<iteration+1;k++) {
  141. // Joint
  142. for(uint32_t phaseId=0;phaseId<jointParallelGroup->numPhases;phaseId++) {
  143. for(uint32_t batchId=0;batchId<jointParallelGroup->numBatches[phaseId];batchId++) {
  144. uint32_t numPairs = jointParallelGroup->numPairs[phaseId*PFX_MAX_SOLVER_BATCHES+batchId];
  145. if(batchId%numTasks == taskId && numPairs > 0) {
  146. const PfxParallelBatch &batch = jointParallelBatches[phaseId*PFX_MAX_SOLVER_BATCHES+batchId];
  147. for(uint32_t i=0;i<numPairs;i++) {
  148. PfxConstraintPair &pair = jointPairs[batch.pairIndices[i]];
  149. uint16_t iA = pfxGetRigidBodyIdA(pair);
  150. uint16_t iB = pfxGetRigidBodyIdB(pair);
  151. PfxSolverBody &solverBodyA = iA != 65535 ? offsetSolverBodies[iA] : staticBody;
  152. PfxSolverBody &solverBodyB = iB != 65535 ? offsetSolverBodies[iB] : staticBody;
  153. if(k==0) {
  154. }
  155. else {
  156. btSolverConstraint* constraintRow = &offsetSolverConstraints[pfxGetContactId1(pair)];
  157. int numRows = pfxGetNumConstraints(pair);
  158. int i;
  159. for (i=0;i<numRows;i++)
  160. {
  161. resolveSingleConstraintRowGeneric(solverBodyA,solverBodyB,constraintRow[i]);
  162. }
  163. }
  164. }
  165. }
  166. }
  167. barrier->sync();
  168. }
  169. // Contact
  170. for(uint32_t phaseId=0;phaseId<contactParallelGroup->numPhases;phaseId++) {
  171. for(uint32_t batchId=0;batchId<contactParallelGroup->numBatches[phaseId];batchId++) {
  172. uint32_t numPairs = contactParallelGroup->numPairs[phaseId*PFX_MAX_SOLVER_BATCHES+batchId];
  173. if(batchId%numTasks == taskId && numPairs > 0) {
  174. const PfxParallelBatch &batch = contactParallelBatches[phaseId*PFX_MAX_SOLVER_BATCHES+batchId];
  175. for(uint32_t i=0;i<numPairs;i++) {
  176. PfxConstraintPair &pair = contactPairs[batch.pairIndices[i]];
  177. uint16_t iA = pfxGetRigidBodyIdA(pair);
  178. uint16_t iB = pfxGetRigidBodyIdB(pair);
  179. uint32_t contactIndex = pfxGetConstraintId1(pair);
  180. btPersistentManifold& contact = offsetContactManifolds[contactIndex];
  181. btConstraintRow* contactConstraintRows = &offsetContactConstraintRows[contactIndex*12];
  182. PfxSolverBody &solverBodyA = offsetSolverBodies[iA];
  183. PfxSolverBody &solverBodyB = offsetSolverBodies[iB];
  184. for(int j=0;j<contact.getNumContacts();j++) {
  185. btManifoldPoint& cp = contact.getContactPoint(j);
  186. if(k==0) {
  187. vmVector3 rA = rotate(solverBodyA.mOrientation,btReadVector3(cp.m_localPointA));
  188. vmVector3 rB = rotate(solverBodyB.mOrientation,btReadVector3(cp.m_localPointB));
  189. float imp[3] =
  190. {
  191. cp.m_appliedImpulse,
  192. cp.m_appliedImpulseLateral1,
  193. cp.m_appliedImpulseLateral2
  194. };
  195. for(int k=0;k<3;k++)
  196. {
  197. vmVector3 normal = btReadVector3(contactConstraintRows[j*3+k].m_normal);
  198. contactConstraintRows[j*3+k].m_accumImpulse = imp[k];
  199. float deltaImpulse = contactConstraintRows[j*3+k].m_accumImpulse;
  200. solverBodyA.mDeltaLinearVelocity += deltaImpulse * solverBodyA.mMassInv * normal;
  201. solverBodyA.mDeltaAngularVelocity += deltaImpulse * solverBodyA.mInertiaInv * cross(rA,normal);
  202. solverBodyB.mDeltaLinearVelocity -= deltaImpulse * solverBodyB.mMassInv * normal;
  203. solverBodyB.mDeltaAngularVelocity -= deltaImpulse * solverBodyB.mInertiaInv * cross(rB,normal);
  204. }
  205. }
  206. else {
  207. btSolveContactConstraint(
  208. contactConstraintRows[j*3],
  209. contactConstraintRows[j*3+1],
  210. contactConstraintRows[j*3+2],
  211. btReadVector3(cp.m_localPointA),
  212. btReadVector3(cp.m_localPointB),
  213. solverBodyA,
  214. solverBodyB,
  215. cp.m_combinedFriction
  216. );
  217. }
  218. }
  219. }
  220. }
  221. }
  222. if (barrier)
  223. barrier->sync();
  224. }
  225. }
  226. }
  227. void CustomPostSolverTask(
  228. TrbState *states,
  229. PfxSolverBody *solverBodies,
  230. uint32_t numRigidBodies)
  231. {
  232. for(uint32_t i=0;i<numRigidBodies;i++) {
  233. TrbState &state = states[i];
  234. PfxSolverBody &solverBody = solverBodies[i];
  235. state.setLinearVelocity(state.getLinearVelocity()+solverBody.mDeltaLinearVelocity);
  236. state.setAngularVelocity(state.getAngularVelocity()+solverBody.mDeltaAngularVelocity);
  237. }
  238. }
  239. void* SolverlsMemoryFunc()
  240. {
  241. //don't create local store memory, just return 0
  242. return 0;
  243. }
  244. static SIMD_FORCE_INLINE
  245. void pfxGetPlaneSpace(const vmVector3& n, vmVector3& p, vmVector3& q)
  246. {
  247. if(fabsf(n[2]) > 0.707f) {
  248. // choose p in y-z plane
  249. float a = n[1]*n[1] + n[2]*n[2];
  250. float k = 1.0f/sqrtf(a);
  251. p[0] = 0;
  252. p[1] = -n[2]*k;
  253. p[2] = n[1]*k;
  254. // set q = n x p
  255. q[0] = a*k;
  256. q[1] = -n[0]*p[2];
  257. q[2] = n[0]*p[1];
  258. }
  259. else {
  260. // choose p in x-y plane
  261. float a = n[0]*n[0] + n[1]*n[1];
  262. float k = 1.0f/sqrtf(a);
  263. p[0] = -n[1]*k;
  264. p[1] = n[0]*k;
  265. p[2] = 0;
  266. // set q = n x p
  267. q[0] = -n[2]*p[1];
  268. q[1] = n[2]*p[0];
  269. q[2] = a*k;
  270. }
  271. }
  272. #define PFX_CONTACT_SLOP 0.001f
  273. void btSetupContactConstraint(
  274. btConstraintRow &constraintResponse,
  275. btConstraintRow &constraintFriction1,
  276. btConstraintRow &constraintFriction2,
  277. float penetrationDepth,
  278. float restitution,
  279. float friction,
  280. const vmVector3 &contactNormal,
  281. const vmVector3 &contactPointA,
  282. const vmVector3 &contactPointB,
  283. const TrbState &stateA,
  284. const TrbState &stateB,
  285. PfxSolverBody &solverBodyA,
  286. PfxSolverBody &solverBodyB,
  287. const vmVector3& linVelA,
  288. const vmVector3& angVelA,
  289. const vmVector3& linVelB,
  290. const vmVector3& angVelB,
  291. float separateBias,
  292. float timeStep
  293. )
  294. {
  295. vmVector3 rA = rotate(solverBodyA.mOrientation,contactPointA);
  296. vmVector3 rB = rotate(solverBodyB.mOrientation,contactPointB);
  297. vmMatrix3 K = vmMatrix3::scale(vmVector3(solverBodyA.mMassInv + solverBodyB.mMassInv)) -
  298. crossMatrix(rA) * solverBodyA.mInertiaInv * crossMatrix(rA) -
  299. crossMatrix(rB) * solverBodyB.mInertiaInv * crossMatrix(rB);
  300. //use the velocities without the applied (gravity and external) forces for restitution computation
  301. vmVector3 vArestitution = linVelA + cross(angVelA,rA);
  302. vmVector3 vBrestitution = linVelB + cross(angVelB,rB);
  303. vmVector3 vABrestitution = vArestitution-vBrestitution;
  304. vmVector3 vA = stateA.getLinearVelocity() + cross(stateA.getAngularVelocity(),rA);
  305. vmVector3 vB = stateB.getLinearVelocity() + cross(stateB.getAngularVelocity(),rB);
  306. vmVector3 vAB = vA-vB;
  307. vmVector3 tangent1,tangent2;
  308. btPlaneSpace1(contactNormal,tangent1,tangent2);
  309. // constraintResponse.m_accumImpulse = 0.f;
  310. // constraintFriction1.m_accumImpulse = 0.f;
  311. // constraintFriction2.m_accumImpulse = 0.f;
  312. // Contact Constraint
  313. {
  314. vmVector3 normal = contactNormal;
  315. float denom = dot(K*normal,normal);
  316. constraintResponse.m_rhs = -(1.0f+restitution)*dot(vAB,normal); // velocity error
  317. constraintResponse.m_rhs -= (separateBias * btMin(0.0f,penetrationDepth+PFX_CONTACT_SLOP)) / timeStep; // position error
  318. constraintResponse.m_rhs /= denom;
  319. constraintResponse.m_jacDiagInv = 1.0f/denom;
  320. constraintResponse.m_lowerLimit = 0.0f;
  321. constraintResponse.m_upperLimit = SIMD_INFINITY;
  322. btStoreVector3(normal,constraintResponse.m_normal);
  323. }
  324. // Friction Constraint 1
  325. {
  326. vmVector3 normal = tangent1;
  327. float denom = dot(K*normal,normal);
  328. constraintFriction1.m_jacDiagInv = 1.0f/denom;
  329. constraintFriction1.m_rhs = -dot(vAB,normal);
  330. constraintFriction1.m_rhs *= constraintFriction1.m_jacDiagInv;
  331. constraintFriction1.m_lowerLimit = 0.0f;
  332. constraintFriction1.m_upperLimit = SIMD_INFINITY;
  333. btStoreVector3(normal,constraintFriction1.m_normal);
  334. }
  335. // Friction Constraint 2
  336. {
  337. vmVector3 normal = tangent2;
  338. float denom = dot(K*normal,normal);
  339. constraintFriction2.m_jacDiagInv = 1.0f/denom;
  340. constraintFriction2.m_rhs = -dot(vAB,normal);
  341. constraintFriction2.m_rhs *= constraintFriction2.m_jacDiagInv;
  342. constraintFriction2.m_lowerLimit = 0.0f;
  343. constraintFriction2.m_upperLimit = SIMD_INFINITY;
  344. btStoreVector3(normal,constraintFriction2.m_normal);
  345. }
  346. }
  347. void CustomSetupContactConstraintsTask(
  348. PfxConstraintPair *contactPairs,uint32_t numContactPairs,
  349. btPersistentManifold* offsetContactManifolds,
  350. btConstraintRow* offsetContactConstraintRows,
  351. TrbState *offsetRigStates,
  352. PfxSolverBody *offsetSolverBodies,
  353. uint32_t numRigidBodies,
  354. float separateBias,
  355. float timeStep)
  356. {
  357. for(uint32_t i=0;i<numContactPairs;i++) {
  358. PfxConstraintPair &pair = contactPairs[i];
  359. if(!pfxGetActive(pair) || pfxGetNumConstraints(pair) == 0 ||
  360. ((pfxGetMotionMaskA(pair)&PFX_MOTION_MASK_STATIC) && (pfxGetMotionMaskB(pair)&PFX_MOTION_MASK_STATIC)) ) {
  361. continue;
  362. }
  363. uint16_t iA = pfxGetRigidBodyIdA(pair);
  364. uint16_t iB = pfxGetRigidBodyIdB(pair);
  365. int id = pfxGetConstraintId1(pair);
  366. btPersistentManifold& contact = offsetContactManifolds[id];
  367. btConstraintRow* contactConstraintRows = &offsetContactConstraintRows[id*12];
  368. TrbState &stateA = offsetRigStates[iA];
  369. // PfxRigBody &bodyA = offsetRigBodies[iA];
  370. PfxSolverBody &solverBodyA = offsetSolverBodies[iA];
  371. TrbState &stateB = offsetRigStates[iB];
  372. // PfxRigBody &bodyB = offsetRigBodies[iB];
  373. PfxSolverBody &solverBodyB = offsetSolverBodies[iB];
  374. float restitution = 0.5f * (solverBodyA.restitution + solverBodyB.restitution);
  375. //if(contact.getDuration() > 1) restitution = 0.0f;
  376. float friction = sqrtf(solverBodyA.friction * solverBodyB.friction);
  377. for(int j=0;j<contact.getNumContacts();j++) {
  378. btManifoldPoint& cp = contact.getContactPoint(j);
  379. //pass the velocities without the applied (gravity and external) forces for restitution computation
  380. const btRigidBody* rbA = btRigidBody::upcast(contact.getBody0());
  381. const btRigidBody* rbB = btRigidBody::upcast(contact.getBody1());
  382. btVector3 linVelA, linVelB;
  383. btVector3 angVelA, angVelB;
  384. if (rbA && (rbA->getInvMass()>0.f))
  385. {
  386. linVelA = rbA->getLinearVelocity();
  387. angVelA = rbA->getAngularVelocity();
  388. } else
  389. {
  390. linVelA.setValue(0,0,0);
  391. angVelA.setValue(0,0,0);
  392. }
  393. if (rbB && (rbB->getInvMass()>0.f))
  394. {
  395. linVelB = rbB->getLinearVelocity();
  396. angVelB = rbB->getAngularVelocity();
  397. } else
  398. {
  399. linVelB.setValue(0,0,0);
  400. angVelB.setValue(0,0,0);
  401. }
  402. btSetupContactConstraint(
  403. contactConstraintRows[j*3],
  404. contactConstraintRows[j*3+1],
  405. contactConstraintRows[j*3+2],
  406. cp.getDistance(),
  407. restitution,
  408. friction,
  409. btReadVector3(cp.m_normalWorldOnB),//.mConstraintRow[0].m_normal),
  410. btReadVector3(cp.m_localPointA),
  411. btReadVector3(cp.m_localPointB),
  412. stateA,
  413. stateB,
  414. solverBodyA,
  415. solverBodyB,
  416. (const vmVector3&)linVelA, (const vmVector3&)angVelA,
  417. (const vmVector3&)linVelB, (const vmVector3&)angVelB,
  418. separateBias,
  419. timeStep
  420. );
  421. }
  422. //contact.setCompositeFriction(friction);
  423. }
  424. }
  425. void CustomWritebackContactConstraintsTask(
  426. PfxConstraintPair *contactPairs,uint32_t numContactPairs,
  427. btPersistentManifold* offsetContactManifolds,
  428. btConstraintRow* offsetContactConstraintRows,
  429. TrbState *offsetRigStates,
  430. PfxSolverBody *offsetSolverBodies,
  431. uint32_t numRigidBodies,
  432. float separateBias,
  433. float timeStep)
  434. {
  435. for(uint32_t i=0;i<numContactPairs;i++) {
  436. PfxConstraintPair &pair = contactPairs[i];
  437. if(!pfxGetActive(pair) || pfxGetNumConstraints(pair) == 0 ||
  438. ((pfxGetMotionMaskA(pair)&PFX_MOTION_MASK_STATIC) && (pfxGetMotionMaskB(pair)&PFX_MOTION_MASK_STATIC)) ) {
  439. continue;
  440. }
  441. int id = pfxGetConstraintId1(pair);
  442. btPersistentManifold& contact = offsetContactManifolds[id];
  443. btConstraintRow* contactConstraintRows = &offsetContactConstraintRows[id*12];
  444. for(int j=0;j<contact.getNumContacts();j++) {
  445. btManifoldPoint& cp = contact.getContactPoint(j);
  446. cp.m_appliedImpulse = contactConstraintRows[j*3+0].m_accumImpulse;
  447. cp.m_appliedImpulseLateral1 = contactConstraintRows[j*3+1].m_accumImpulse;
  448. cp.m_appliedImpulseLateral2 = contactConstraintRows[j*3+2].m_accumImpulse;
  449. }
  450. //contact.setCompositeFriction(friction);
  451. }
  452. }
  453. void SolverThreadFunc(void* userPtr,void* lsMemory)
  454. {
  455. btConstraintSolverIO* io = (btConstraintSolverIO*)(userPtr);//arg->io);
  456. btCriticalSection* criticalsection = io->setupContactConstraints.criticalSection;
  457. //CustomCriticalSection *criticalsection = &io->m_cs;
  458. switch(io->cmd) {
  459. case PFX_CONSTRAINT_SOLVER_CMD_SOLVE_CONSTRAINTS:
  460. CustomSolveConstraintsTaskParallel(
  461. io->solveConstraints.contactParallelGroup,
  462. io->solveConstraints.contactParallelBatches,
  463. io->solveConstraints.contactPairs,
  464. io->solveConstraints.numContactPairs,
  465. io->solveConstraints.offsetContactManifolds,
  466. io->solveConstraints.offsetContactConstraintRows,
  467. io->solveConstraints.jointParallelGroup,
  468. io->solveConstraints.jointParallelBatches,
  469. io->solveConstraints.jointPairs,
  470. io->solveConstraints.numJointPairs,
  471. io->solveConstraints.offsetSolverConstraints,
  472. io->solveConstraints.offsetRigStates1,
  473. io->solveConstraints.offsetSolverBodies,
  474. io->solveConstraints.numRigidBodies,
  475. io->solveConstraints.iteration,
  476. io->solveConstraints.taskId,
  477. io->maxTasks1,
  478. io->solveConstraints.barrier
  479. );
  480. break;
  481. case PFX_CONSTRAINT_SOLVER_CMD_POST_SOLVER:
  482. CustomPostSolverTask( io->postSolver.states,io->postSolver.solverBodies, io->postSolver.numRigidBodies);
  483. break;
  484. case PFX_CONSTRAINT_SOLVER_CMD_SETUP_CONTACT_CONSTRAINTS:
  485. {
  486. bool empty = false;
  487. while(!empty) {
  488. int start,batch;
  489. criticalsection->lock();
  490. start = (int)criticalsection->getSharedParam(0);
  491. batch = (int)criticalsection->getSharedParam(1);
  492. //PFX_PRINTF("taskId %d start %d num %d\n",arg->taskId,start,batch);
  493. // 次のバッファをセット
  494. int nextStart = start + batch;
  495. int rest = btMax((int)io->setupContactConstraints.numContactPairs1 - nextStart,0);
  496. int nextBatch = (rest > batch)?batch:rest;
  497. criticalsection->setSharedParam(0,nextStart);
  498. criticalsection->setSharedParam(1,nextBatch);
  499. criticalsection->unlock();
  500. if(batch > 0) {
  501. CustomSetupContactConstraintsTask(
  502. io->setupContactConstraints.offsetContactPairs+start,batch,
  503. io->setupContactConstraints.offsetContactManifolds,
  504. io->setupContactConstraints.offsetContactConstraintRows,
  505. io->setupContactConstraints.offsetRigStates,
  506. // io->setupContactConstraints.offsetRigBodies,
  507. io->setupContactConstraints.offsetSolverBodies,
  508. io->setupContactConstraints.numRigidBodies,
  509. io->setupContactConstraints.separateBias,
  510. io->setupContactConstraints.timeStep);
  511. }
  512. else {
  513. empty = true;
  514. }
  515. }
  516. }
  517. break;
  518. case PFX_CONSTRAINT_SOLVER_CMD_WRITEBACK_APPLIED_IMPULSES_CONTACT_CONSTRAINTS:
  519. {
  520. bool empty = false;
  521. while(!empty) {
  522. int start,batch;
  523. criticalsection->lock();
  524. start = (int)criticalsection->getSharedParam(0);
  525. batch = (int)criticalsection->getSharedParam(1);
  526. //PFX_PRINTF("taskId %d start %d num %d\n",arg->taskId,start,batch);
  527. // 次のバッファをセット
  528. int nextStart = start + batch;
  529. int rest = btMax((int)io->setupContactConstraints.numContactPairs1 - nextStart,0);
  530. int nextBatch = (rest > batch)?batch:rest;
  531. criticalsection->setSharedParam(0,nextStart);
  532. criticalsection->setSharedParam(1,nextBatch);
  533. criticalsection->unlock();
  534. if(batch > 0) {
  535. CustomWritebackContactConstraintsTask(
  536. io->setupContactConstraints.offsetContactPairs+start,batch,
  537. io->setupContactConstraints.offsetContactManifolds,
  538. io->setupContactConstraints.offsetContactConstraintRows,
  539. io->setupContactConstraints.offsetRigStates,
  540. // io->setupContactConstraints.offsetRigBodies,
  541. io->setupContactConstraints.offsetSolverBodies,
  542. io->setupContactConstraints.numRigidBodies,
  543. io->setupContactConstraints.separateBias,
  544. io->setupContactConstraints.timeStep);
  545. }
  546. else {
  547. empty = true;
  548. }
  549. }
  550. }
  551. break;
  552. default:
  553. {
  554. btAssert(0);
  555. }
  556. }
  557. }
  558. void CustomSetupContactConstraintsNew(
  559. PfxConstraintPair *contactPairs1,uint32_t numContactPairs,
  560. btPersistentManifold *offsetContactManifolds,
  561. btConstraintRow* offsetContactConstraintRows,
  562. TrbState *offsetRigStates,
  563. PfxSolverBody *offsetSolverBodies,
  564. uint32_t numRigidBodies,
  565. float separationBias,
  566. float timeStep,
  567. class btThreadSupportInterface* threadSupport,
  568. btCriticalSection* criticalSection,
  569. btConstraintSolverIO *io ,
  570. uint8_t cmd
  571. )
  572. {
  573. int maxTasks = threadSupport->getNumTasks();
  574. int div = (int)maxTasks * 4;
  575. int batch = ((int)numContactPairs + div - 1) / div;
  576. #ifdef __PPU__
  577. BulletPE2ConstraintSolverSpursSupport* spursThread = (BulletPE2ConstraintSolverSpursSupport*) threadSupport;
  578. #endif
  579. if (criticalSection)
  580. {
  581. criticalSection->setSharedParam(0,0);
  582. criticalSection->setSharedParam(1,btMin(batch,64)); // batched number
  583. } else
  584. {
  585. #ifdef __PPU__
  586. spursThread->setSharedParam(0,0);
  587. spursThread->setSharedParam(1,btMin(batch,64)); // batched number
  588. #endif //__PPU__
  589. }
  590. for(int t=0;t<maxTasks;t++) {
  591. io[t].cmd = cmd;
  592. io[t].setupContactConstraints.offsetContactPairs = contactPairs1;
  593. io[t].setupContactConstraints.numContactPairs1 = numContactPairs;
  594. io[t].setupContactConstraints.offsetRigStates = offsetRigStates;
  595. io[t].setupContactConstraints.offsetContactManifolds = offsetContactManifolds;
  596. io[t].setupContactConstraints.offsetContactConstraintRows = offsetContactConstraintRows;
  597. io[t].setupContactConstraints.offsetSolverBodies = offsetSolverBodies;
  598. io[t].setupContactConstraints.numRigidBodies = numRigidBodies;
  599. io[t].setupContactConstraints.separateBias = separationBias;
  600. io[t].setupContactConstraints.timeStep = timeStep;
  601. io[t].setupContactConstraints.criticalSection = criticalSection;
  602. io[t].maxTasks1 = maxTasks;
  603. #ifdef __PPU__
  604. io[t].barrierAddr2 = (unsigned int)spursThread->getBarrierAddress();
  605. io[t].criticalsectionAddr2 = (unsigned int)spursThread->getCriticalSectionAddress();
  606. #endif
  607. //#define SEQUENTIAL_SETUP
  608. #ifdef SEQUENTIAL_SETUP
  609. CustomSetupContactConstraintsTask(contactPairs1,numContactPairs,offsetContactManifolds,offsetRigStates,offsetSolverBodies,numRigidBodies,separationBias,timeStep);
  610. #else
  611. threadSupport->sendRequest(1,(ppu_address_t)&io[t],t);
  612. #endif
  613. }
  614. #ifndef SEQUENTIAL_SETUP
  615. unsigned int arg0,arg1;
  616. for(int t=0;t<maxTasks;t++) {
  617. arg0 = t;
  618. threadSupport->waitForResponse(&arg0,&arg1);
  619. }
  620. #endif //SEQUENTIAL_SETUP
  621. }
  622. void CustomSplitConstraints(
  623. PfxConstraintPair *pairs,uint32_t numPairs,
  624. PfxParallelGroup &group,PfxParallelBatch *batches,
  625. uint32_t numTasks,
  626. uint32_t numRigidBodies,
  627. void *poolBuff,
  628. uint32_t poolBytes
  629. )
  630. {
  631. HeapManager pool((unsigned char*)poolBuff,poolBytes);
  632. // ステートチェック用ビットフラグテーブル
  633. int bufSize = sizeof(uint8_t)*numRigidBodies;
  634. bufSize = ((bufSize+127)>>7)<<7; // 128 bytes alignment
  635. uint8_t *bodyTable = (uint8_t*)pool.allocate(bufSize,HeapManager::ALIGN128);
  636. // ペアチェック用ビットフラグテーブル
  637. uint32_t *pairTable;
  638. size_t allocSize = sizeof(uint32_t)*((numPairs+31)/32);
  639. pairTable = (uint32_t*)pool.allocate(allocSize);
  640. memset(pairTable,0,allocSize);
  641. // 目標とする分割数
  642. uint32_t targetCount = btMax(uint32_t(PFX_MIN_SOLVER_PAIRS),btMin(numPairs / (numTasks*2),uint32_t(PFX_MAX_SOLVER_PAIRS)));
  643. uint32_t startIndex = 0;
  644. uint32_t phaseId;
  645. uint32_t batchId;
  646. uint32_t totalCount=0;
  647. uint32_t maxBatches = btMin(numTasks,uint32_t(PFX_MAX_SOLVER_BATCHES));
  648. for(phaseId=0;phaseId<PFX_MAX_SOLVER_PHASES&&totalCount<numPairs;phaseId++) {
  649. bool startIndexCheck = true;
  650. group.numBatches[phaseId] = 0;
  651. uint32_t i = startIndex;
  652. // チェック用ビットフラグテーブルをクリア
  653. memset(bodyTable,0xff,bufSize);
  654. for(batchId=0;i<numPairs&&totalCount<numPairs&&batchId<maxBatches;batchId++) {
  655. uint32_t pairCount=0;
  656. PfxParallelBatch &batch = batches[phaseId*PFX_MAX_SOLVER_BATCHES+batchId];
  657. uint32_t pairId = 0;
  658. for(;i<numPairs&&pairCount<targetCount;i++) {
  659. uint32_t idxP = i>>5;
  660. uint32_t maskP = 1L << (i & 31);
  661. //pair is already assigned to a phase/batch
  662. if(pairTable[idxP] & maskP) {
  663. continue;
  664. }
  665. uint32_t idxA = pfxGetRigidBodyIdA(pairs[i]);
  666. uint32_t idxB = pfxGetRigidBodyIdB(pairs[i]);
  667. // 両方ともアクティブでない、または衝突点が0のペアは登録対象からはずす
  668. if(!pfxGetActive(pairs[i]) || pfxGetNumConstraints(pairs[i]) == 0 ||
  669. ((pfxGetMotionMaskA(pairs[i])&PFX_MOTION_MASK_STATIC) && (pfxGetMotionMaskB(pairs[i])&PFX_MOTION_MASK_STATIC)) ) {
  670. if(startIndexCheck)
  671. startIndex++;
  672. //assign pair -> skip it because it has no constraints
  673. pairTable[idxP] |= maskP;
  674. totalCount++;
  675. continue;
  676. }
  677. // 依存性のチェック
  678. if( (bodyTable[idxA] != batchId && bodyTable[idxA] != 0xff) ||
  679. (bodyTable[idxB] != batchId && bodyTable[idxB] != 0xff) ) {
  680. startIndexCheck = false;
  681. //bodies of the pair are already assigned to another batch within this phase
  682. continue;
  683. }
  684. // 依存性判定テーブルに登録
  685. if(pfxGetMotionMaskA(pairs[i])&PFX_MOTION_MASK_DYNAMIC)
  686. bodyTable[idxA] = batchId;
  687. if(pfxGetMotionMaskB(pairs[i])&PFX_MOTION_MASK_DYNAMIC)
  688. bodyTable[idxB] = batchId;
  689. if(startIndexCheck)
  690. startIndex++;
  691. pairTable[idxP] |= maskP;
  692. //add the pair 'i' to the current batch
  693. batch.pairIndices[pairId++] = i;
  694. pairCount++;
  695. }
  696. group.numPairs[phaseId*PFX_MAX_SOLVER_BATCHES+batchId] = (uint16_t)pairId;
  697. totalCount += pairCount;
  698. }
  699. group.numBatches[phaseId] = batchId;
  700. }
  701. group.numPhases = phaseId;
  702. pool.clear();
  703. }
  704. void CustomSolveConstraintsParallel(
  705. PfxConstraintPair *contactPairs,uint32_t numContactPairs,
  706. PfxConstraintPair *jointPairs,uint32_t numJointPairs,
  707. btPersistentManifold* offsetContactManifolds,
  708. btConstraintRow* offsetContactConstraintRows,
  709. btSolverConstraint* offsetSolverConstraints,
  710. TrbState *offsetRigStates,
  711. PfxSolverBody *offsetSolverBodies,
  712. uint32_t numRigidBodies,
  713. struct btConstraintSolverIO* io,
  714. class btThreadSupportInterface* threadSupport,
  715. int iteration,
  716. void* poolBuf,
  717. int poolBytes,
  718. class btBarrier* barrier)
  719. {
  720. int maxTasks = threadSupport->getNumTasks();
  721. // config.taskManager->setTaskEntry(PFX_SOLVER_ENTRY);
  722. HeapManager pool((unsigned char*)poolBuf,poolBytes);
  723. {
  724. PfxParallelGroup *cgroup = (PfxParallelGroup*)pool.allocate(sizeof(PfxParallelGroup));
  725. PfxParallelBatch *cbatches = (PfxParallelBatch*)pool.allocate(sizeof(PfxParallelBatch)*(PFX_MAX_SOLVER_PHASES*PFX_MAX_SOLVER_BATCHES),128);
  726. PfxParallelGroup *jgroup = (PfxParallelGroup*)pool.allocate(sizeof(PfxParallelGroup));
  727. PfxParallelBatch *jbatches = (PfxParallelBatch*)pool.allocate(sizeof(PfxParallelBatch)*(PFX_MAX_SOLVER_PHASES*PFX_MAX_SOLVER_BATCHES),128);
  728. uint32_t tmpBytes = poolBytes - 2 * (sizeof(PfxParallelGroup) + sizeof(PfxParallelBatch)*(PFX_MAX_SOLVER_PHASES*PFX_MAX_SOLVER_BATCHES) + 128);
  729. void *tmpBuff = pool.allocate(tmpBytes);
  730. {
  731. BT_PROFILE("CustomSplitConstraints");
  732. CustomSplitConstraints(contactPairs,numContactPairs,*cgroup,cbatches,maxTasks,numRigidBodies,tmpBuff,tmpBytes);
  733. CustomSplitConstraints(jointPairs,numJointPairs,*jgroup,jbatches,maxTasks,numRigidBodies,tmpBuff,tmpBytes);
  734. }
  735. {
  736. BT_PROFILE("PFX_CONSTRAINT_SOLVER_CMD_SOLVE_CONSTRAINTS");
  737. //#define SOLVE_SEQUENTIAL
  738. #ifdef SOLVE_SEQUENTIAL
  739. CustomSolveConstraintsTask(
  740. io->solveConstraints.contactParallelGroup,
  741. io->solveConstraints.contactParallelBatches,
  742. io->solveConstraints.contactPairs,
  743. io->solveConstraints.numContactPairs,
  744. io->solveConstraints.offsetContactManifolds,
  745. io->solveConstraints.jointParallelGroup,
  746. io->solveConstraints.jointParallelBatches,
  747. io->solveConstraints.jointPairs,
  748. io->solveConstraints.numJointPairs,
  749. io->solveConstraints.offsetSolverConstraints,
  750. io->solveConstraints.offsetRigStates1,
  751. io->solveConstraints.offsetSolverBodies,
  752. io->solveConstraints.numRigidBodies,
  753. io->solveConstraints.iteration,0,1,0);//arg->taskId,1,0);//,arg->maxTasks,arg->barrier);
  754. #else
  755. for(int t=0;t<maxTasks;t++) {
  756. io[t].cmd = PFX_CONSTRAINT_SOLVER_CMD_SOLVE_CONSTRAINTS;
  757. io[t].solveConstraints.contactParallelGroup = cgroup;
  758. io[t].solveConstraints.contactParallelBatches = cbatches;
  759. io[t].solveConstraints.contactPairs = contactPairs;
  760. io[t].solveConstraints.numContactPairs = numContactPairs;
  761. io[t].solveConstraints.offsetContactManifolds = offsetContactManifolds;
  762. io[t].solveConstraints.offsetContactConstraintRows = offsetContactConstraintRows;
  763. io[t].solveConstraints.jointParallelGroup = jgroup;
  764. io[t].solveConstraints.jointParallelBatches = jbatches;
  765. io[t].solveConstraints.jointPairs = jointPairs;
  766. io[t].solveConstraints.numJointPairs = numJointPairs;
  767. io[t].solveConstraints.offsetSolverConstraints = offsetSolverConstraints;
  768. io[t].solveConstraints.offsetRigStates1 = offsetRigStates;
  769. io[t].solveConstraints.offsetSolverBodies = offsetSolverBodies;
  770. io[t].solveConstraints.numRigidBodies = numRigidBodies;
  771. io[t].solveConstraints.iteration = iteration;
  772. io[t].solveConstraints.taskId = t;
  773. io[t].solveConstraints.barrier = barrier;
  774. io[t].maxTasks1 = maxTasks;
  775. #ifdef __PPU__
  776. BulletPE2ConstraintSolverSpursSupport* spursThread = (BulletPE2ConstraintSolverSpursSupport*) threadSupport;
  777. io[t].barrierAddr2 = (unsigned int) spursThread->getBarrierAddress();
  778. io[t].criticalsectionAddr2 = (unsigned int)spursThread->getCriticalSectionAddress();
  779. #endif
  780. threadSupport->sendRequest(1,(ppu_address_t)&io[t],t);
  781. }
  782. unsigned int arg0,arg1;
  783. for(int t=0;t<maxTasks;t++) {
  784. arg0 = t;
  785. threadSupport->waitForResponse(&arg0,&arg1);
  786. }
  787. #endif
  788. }
  789. pool.clear();
  790. }
  791. {
  792. BT_PROFILE("PFX_CONSTRAINT_SOLVER_CMD_POST_SOLVER");
  793. int batch = ((int)numRigidBodies + maxTasks - 1) / maxTasks;
  794. int rest = (int)numRigidBodies;
  795. int start = 0;
  796. for(int t=0;t<maxTasks;t++) {
  797. int num = (rest - batch ) > 0 ? batch : rest;
  798. io[t].cmd = PFX_CONSTRAINT_SOLVER_CMD_POST_SOLVER;
  799. io[t].postSolver.states = offsetRigStates + start;
  800. io[t].postSolver.solverBodies = offsetSolverBodies + start;
  801. io[t].postSolver.numRigidBodies = (uint32_t)num;
  802. io[t].maxTasks1 = maxTasks;
  803. #ifdef __PPU__
  804. BulletPE2ConstraintSolverSpursSupport* spursThread = (BulletPE2ConstraintSolverSpursSupport*) threadSupport;
  805. io[t].barrierAddr2 = (unsigned int)spursThread->getBarrierAddress();
  806. io[t].criticalsectionAddr2 = (unsigned int)spursThread->getCriticalSectionAddress();
  807. #endif
  808. #ifdef SOLVE_SEQUENTIAL
  809. CustomPostSolverTask( io[t].postSolver.states,io[t].postSolver.solverBodies, io[t].postSolver.numRigidBodies);
  810. #else
  811. threadSupport->sendRequest(1,(ppu_address_t)&io[t],t);
  812. #endif
  813. rest -= num;
  814. start += num;
  815. }
  816. unsigned int arg0,arg1;
  817. for(int t=0;t<maxTasks;t++) {
  818. #ifndef SOLVE_SEQUENTIAL
  819. arg0 = t;
  820. threadSupport->waitForResponse(&arg0,&arg1);
  821. #endif
  822. }
  823. }
  824. }
  825. void BPE_customConstraintSolverSequentialNew(unsigned int new_num, PfxBroadphasePair *new_pairs1 ,
  826. btPersistentManifold* offsetContactManifolds,
  827. PfxConstraintRow* offsetContactConstraintRows,
  828. TrbState* states,int numRigidBodies,
  829. struct PfxSolverBody* solverBodies,
  830. PfxConstraintPair* jointPairs, unsigned int numJoints,
  831. btSolverConstraint* offsetSolverConstraints,
  832. float separateBias,
  833. float timeStep,
  834. int iteration,
  835. btThreadSupportInterface* solverThreadSupport,
  836. btCriticalSection* criticalSection,
  837. struct btConstraintSolverIO* solverIO,
  838. btBarrier* barrier
  839. )
  840. {
  841. {
  842. BT_PROFILE("pfxSetupConstraints");
  843. for(uint32_t i=0;i<numJoints;i++) {
  844. // 情報の更新
  845. PfxConstraintPair &pair = jointPairs[i];
  846. int idA = pfxGetRigidBodyIdA(pair);
  847. if (idA != 65535)
  848. {
  849. pfxSetMotionMaskA(pair,states[pfxGetRigidBodyIdA(pair)].getMotionMask());
  850. }
  851. else
  852. {
  853. pfxSetMotionMaskA(pair,PFX_MOTION_MASK_STATIC);
  854. }
  855. int idB = pfxGetRigidBodyIdB(pair);
  856. if (idB!= 65535)
  857. {
  858. pfxSetMotionMaskB(pair,states[pfxGetRigidBodyIdB(pair)].getMotionMask());
  859. } else
  860. {
  861. pfxSetMotionMaskB(pair,PFX_MOTION_MASK_STATIC);
  862. }
  863. }
  864. // CustomSetupJointConstraintsSeq( jointPairs,numJoints,joints, states, solverBodies, numRigidBodies, timeStep);
  865. #ifdef SEQUENTIAL_SETUP
  866. CustomSetupContactConstraintsSeqNew(
  867. (PfxConstraintPair*)new_pairs1,new_num,contacts,
  868. states,
  869. solverBodies,
  870. numRigidBodies,
  871. separateBias,
  872. timeStep);
  873. #else
  874. CustomSetupContactConstraintsNew(
  875. (PfxConstraintPair*)new_pairs1,new_num,
  876. offsetContactManifolds,
  877. offsetContactConstraintRows,
  878. states,
  879. solverBodies,
  880. numRigidBodies,
  881. separateBias,
  882. timeStep,
  883. solverThreadSupport,
  884. criticalSection,solverIO,
  885. PFX_CONSTRAINT_SOLVER_CMD_SETUP_CONTACT_CONSTRAINTS
  886. );
  887. #endif //SEQUENTIAL_SETUP
  888. }
  889. {
  890. BT_PROFILE("pfxSolveConstraints");
  891. //#define SEQUENTIAL
  892. #ifdef SEQUENTIAL
  893. CustomSolveConstraintsSeq(
  894. (PfxConstraintPair*)new_pairs1,new_num,contacts,
  895. jointPairs,numJoints,
  896. states,
  897. solverBodies,
  898. numRigidBodies,
  899. separateBias,
  900. timeStep,
  901. iteration);
  902. #else //SEQUENTIAL
  903. CustomSolveConstraintsParallel(
  904. (PfxConstraintPair*)new_pairs1,new_num,
  905. jointPairs,numJoints,
  906. offsetContactManifolds,
  907. offsetContactConstraintRows,
  908. offsetSolverConstraints,
  909. states,
  910. solverBodies,
  911. numRigidBodies,
  912. solverIO, solverThreadSupport,
  913. iteration,
  914. tmp_buff,
  915. TMP_BUFF_BYTES,
  916. barrier
  917. );
  918. #endif //SEQUENTIAL
  919. }
  920. {
  921. BT_PROFILE("writeback appliedImpulses");
  922. CustomSetupContactConstraintsNew(
  923. (PfxConstraintPair*)new_pairs1,new_num,
  924. offsetContactManifolds,
  925. offsetContactConstraintRows,
  926. states,
  927. solverBodies,
  928. numRigidBodies,
  929. separateBias,
  930. timeStep,
  931. solverThreadSupport,
  932. criticalSection,solverIO,
  933. PFX_CONSTRAINT_SOLVER_CMD_WRITEBACK_APPLIED_IMPULSES_CONTACT_CONSTRAINTS
  934. );
  935. }
  936. }
  937. struct btParallelSolverMemoryCache
  938. {
  939. btAlignedObjectArray<TrbState> m_mystates;
  940. btAlignedObjectArray<PfxSolverBody> m_mysolverbodies;
  941. btAlignedObjectArray<PfxBroadphasePair> m_mypairs;
  942. btAlignedObjectArray<PfxConstraintPair> m_jointPairs;
  943. btAlignedObjectArray<PfxConstraintRow> m_constraintRows;
  944. };
  945. btConstraintSolverIO* createSolverIO(int numThreads)
  946. {
  947. return new btConstraintSolverIO[numThreads];
  948. }
  949. btParallelConstraintSolver::btParallelConstraintSolver(btThreadSupportInterface* solverThreadSupport)
  950. {
  951. m_solverThreadSupport = solverThreadSupport;//createSolverThreadSupport(maxNumThreads);
  952. m_solverIO = createSolverIO(m_solverThreadSupport->getNumTasks());
  953. m_barrier = m_solverThreadSupport->createBarrier();
  954. m_criticalSection = m_solverThreadSupport->createCriticalSection();
  955. m_memoryCache = new btParallelSolverMemoryCache();
  956. }
  957. btParallelConstraintSolver::~btParallelConstraintSolver()
  958. {
  959. delete m_memoryCache;
  960. delete m_solverIO;
  961. m_solverThreadSupport->deleteBarrier(m_barrier);
  962. m_solverThreadSupport->deleteCriticalSection(m_criticalSection);
  963. }
  964. btScalar btParallelConstraintSolver::solveGroup(btCollisionObject** bodies1,int numRigidBodies,btPersistentManifold** manifoldPtr,int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer,btDispatcher* dispatcher)
  965. {
  966. /* int sz = sizeof(PfxSolverBody);
  967. int sz2 = sizeof(vmVector3);
  968. int sz3 = sizeof(vmMatrix3);
  969. int sz4 = sizeof(vmQuat);
  970. int sz5 = sizeof(btConstraintRow);
  971. int sz6 = sizeof(btSolverConstraint);
  972. int sz7 = sizeof(TrbState);
  973. */
  974. btPersistentManifold* offsetContactManifolds= (btPersistentManifold*) dispatcher->getInternalManifoldPool()->getPoolAddress();
  975. m_memoryCache->m_mysolverbodies.resize(numRigidBodies);
  976. m_memoryCache->m_mystates.resize(numRigidBodies);
  977. {
  978. BT_PROFILE("create states and solver bodies");
  979. for (int i=0;i<numRigidBodies;i++)
  980. {
  981. btCollisionObject* obj = bodies1[i];
  982. obj->setCompanionId(i);
  983. PfxSolverBody& solverBody = m_memoryCache->m_mysolverbodies[i];
  984. btRigidBody* rb = btRigidBody::upcast(obj);
  985. TrbState& state = m_memoryCache->m_mystates[i];
  986. state.reset();
  987. const btQuaternion& orgOri = obj->getWorldTransform().getRotation();
  988. vmQuat orn(orgOri.getX(),orgOri.getY(),orgOri.getZ(),orgOri.getW());
  989. state.setPosition(getVmVector3(obj->getWorldTransform().getOrigin()));
  990. state.setOrientation(orn);
  991. state.setPosition(state.getPosition());
  992. state.setRigidBodyId(i);
  993. state.setAngularDamping(0);
  994. state.setLinearDamping(0);
  995. solverBody.mOrientation = state.getOrientation();
  996. solverBody.mDeltaLinearVelocity = vmVector3(0.0f);
  997. solverBody.mDeltaAngularVelocity = vmVector3(0.0f);
  998. solverBody.friction = obj->getFriction();
  999. solverBody.restitution = obj->getRestitution();
  1000. state.resetSleepCount();
  1001. //if(state.getMotionMask()&PFX_MOTION_MASK_DYNAMIC) {
  1002. if (rb && (rb->getInvMass()>0.f))
  1003. {
  1004. btVector3 angVelPlusForces = rb->getAngularVelocity()+rb->getTotalTorque()*rb->getInvInertiaTensorWorld()*infoGlobal.m_timeStep;
  1005. btVector3 linVelPlusForces = rb->getLinearVelocity()+rb->getTotalForce()*rb->getInvMass()*infoGlobal.m_timeStep;
  1006. state.setAngularVelocity(btReadVector3(angVelPlusForces));
  1007. state.setLinearVelocity(btReadVector3(linVelPlusForces));
  1008. state.setMotionType(PfxMotionTypeActive);
  1009. vmMatrix3 ori(solverBody.mOrientation);
  1010. vmMatrix3 localInvInertia = vmMatrix3::identity();
  1011. localInvInertia.setCol(0,vmVector3(rb->getInvInertiaDiagLocal().getX(),0,0));
  1012. localInvInertia.setCol(1,vmVector3(0, rb->getInvInertiaDiagLocal().getY(),0));
  1013. localInvInertia.setCol(2,vmVector3(0,0, rb->getInvInertiaDiagLocal().getZ()));
  1014. solverBody.mMassInv = rb->getInvMass();
  1015. solverBody.mInertiaInv = ori * localInvInertia * transpose(ori);
  1016. } else
  1017. {
  1018. state.setAngularVelocity(vmVector3(0));
  1019. state.setLinearVelocity(vmVector3(0));
  1020. state.setMotionType(PfxMotionTypeFixed);
  1021. m_memoryCache->m_mysolverbodies[i].mMassInv = 0.f;
  1022. m_memoryCache->m_mysolverbodies[i].mInertiaInv = vmMatrix3(0.0f);
  1023. }
  1024. }
  1025. }
  1026. int totalPoints = 0;
  1027. #ifndef USE_C_ARRAYS
  1028. m_memoryCache->m_mypairs.resize(numManifolds);
  1029. //4 points per manifold and 3 rows per point makes 12 rows per manifold
  1030. m_memoryCache->m_constraintRows.resize(numManifolds*12);
  1031. m_memoryCache->m_jointPairs.resize(numConstraints);
  1032. #endif//USE_C_ARRAYS
  1033. int actualNumManifolds= 0;
  1034. {
  1035. BT_PROFILE("convert manifolds");
  1036. for (int i1=0;i1<numManifolds;i1++)
  1037. {
  1038. if (manifoldPtr[i1]->getNumContacts()>0)
  1039. {
  1040. btPersistentManifold* m = manifoldPtr[i1];
  1041. btCollisionObject* obA = (btCollisionObject*)m->getBody0();
  1042. btCollisionObject* obB = (btCollisionObject*)m->getBody1();
  1043. bool obAisActive = !obA->isStaticOrKinematicObject() && obA->isActive();
  1044. bool obBisActive = !obB->isStaticOrKinematicObject() && obB->isActive();
  1045. if (!obAisActive && !obBisActive)
  1046. continue;
  1047. //int contactId = i1;//actualNumManifolds;
  1048. PfxBroadphasePair& pair = m_memoryCache->m_mypairs[actualNumManifolds];
  1049. //init those
  1050. // float compFric = obA->getFriction()*obB->getFriction();//@todo
  1051. int idA = obA->getCompanionId();
  1052. int idB = obB->getCompanionId();
  1053. m->m_companionIdA = idA;
  1054. m->m_companionIdB = idB;
  1055. // if ((mysolverbodies[idA].mMassInv!=0)&&(mysolverbodies[idB].mMassInv!=0))
  1056. // continue;
  1057. int numPosPoints=0;
  1058. for (int p=0;p<m->getNumContacts();p++)
  1059. {
  1060. //btManifoldPoint& pt = m->getContactPoint(p);
  1061. //float dist = pt.getDistance();
  1062. //if (dist<0.001)
  1063. numPosPoints++;
  1064. }
  1065. totalPoints+=numPosPoints;
  1066. pfxSetRigidBodyIdA(pair,idA);
  1067. pfxSetRigidBodyIdB(pair,idB);
  1068. pfxSetMotionMaskA(pair,m_memoryCache->m_mystates[idA].getMotionMask());
  1069. pfxSetMotionMaskB(pair,m_memoryCache->m_mystates[idB].getMotionMask());
  1070. pfxSetActive(pair,numPosPoints>0);
  1071. pfxSetBroadphaseFlag(pair,0);
  1072. int contactId = m-offsetContactManifolds;
  1073. //likely the contact pool is not contiguous, make sure to allocate large enough contact pool
  1074. btAssert(contactId>=0);
  1075. btAssert(contactId<dispatcher->getInternalManifoldPool()->getMaxCount());
  1076. pfxSetContactId(pair,contactId);
  1077. pfxSetNumConstraints(pair,numPosPoints);//manifoldPtr[i]->getNumContacts());
  1078. actualNumManifolds++;
  1079. }
  1080. }
  1081. }
  1082. PfxConstraintPair* jointPairs=0;
  1083. jointPairs = numConstraints? &m_memoryCache->m_jointPairs[0]:0;
  1084. int actualNumJoints=0;
  1085. btSolverConstraint* offsetSolverConstraints = 0;
  1086. //if (1)
  1087. {
  1088. {
  1089. BT_PROFILE("convert constraints");
  1090. int totalNumRows = 0;
  1091. int i;
  1092. m_tmpConstraintSizesPool.resize(numConstraints);
  1093. //calculate the total number of contraint rows
  1094. for (i=0;i<numConstraints;i++)
  1095. {
  1096. btTypedConstraint::btConstraintInfo1& info1 = m_tmpConstraintSizesPool[i];
  1097. constraints[i]->getInfo1(&info1);
  1098. totalNumRows += info1.m_numConstraintRows;
  1099. }
  1100. m_tmpSolverNonContactConstraintPool.resize(totalNumRows);
  1101. offsetSolverConstraints =totalNumRows? &m_tmpSolverNonContactConstraintPool[0]:0;
  1102. ///setup the btSolverConstraints
  1103. int currentRow = 0;
  1104. for (i=0;i<numConstraints;i++)
  1105. {
  1106. const btTypedConstraint::btConstraintInfo1& info1 = m_tmpConstraintSizesPool[i];
  1107. if (info1.m_numConstraintRows)
  1108. {
  1109. btAssert(currentRow<totalNumRows);
  1110. btTypedConstraint* constraint = constraints[i];
  1111. btSolverConstraint* currentConstraintRow = &m_tmpSolverNonContactConstraintPool[currentRow];
  1112. btRigidBody& rbA = constraint->getRigidBodyA();
  1113. btRigidBody& rbB = constraint->getRigidBodyB();
  1114. int idA = constraint->getRigidBodyA().getCompanionId();
  1115. int idB = constraint->getRigidBodyB().getCompanionId();
  1116. int j;
  1117. for ( j=0;j<info1.m_numConstraintRows;j++)
  1118. {
  1119. memset(&currentConstraintRow[j],0,sizeof(btSolverConstraint));
  1120. currentConstraintRow[j].m_lowerLimit = -FLT_MAX;
  1121. currentConstraintRow[j].m_upperLimit = FLT_MAX;
  1122. currentConstraintRow[j].m_appliedImpulse = 0.f;
  1123. currentConstraintRow[j].m_appliedPushImpulse = 0.f;
  1124. currentConstraintRow[j].m_solverBodyIdA = idA;
  1125. currentConstraintRow[j].m_solverBodyIdB = idB;
  1126. }
  1127. btTypedConstraint::btConstraintInfo2 info2;
  1128. info2.fps = 1.f/infoGlobal.m_timeStep;
  1129. info2.erp = infoGlobal.m_erp;
  1130. info2.m_J1linearAxis = currentConstraintRow->m_contactNormal1;
  1131. info2.m_J1angularAxis = currentConstraintRow->m_relpos1CrossNormal;
  1132. info2.m_J2linearAxis = currentConstraintRow->m_contactNormal2;
  1133. info2.m_J2angularAxis = currentConstraintRow->m_relpos2CrossNormal;
  1134. info2.rowskip = sizeof(btSolverConstraint)/sizeof(btScalar);//check this
  1135. ///the size of btSolverConstraint needs be a multiple of btScalar
  1136. btAssert(info2.rowskip*sizeof(btScalar)== sizeof(btSolverConstraint));
  1137. info2.m_constraintError = &currentConstraintRow->m_rhs;
  1138. currentConstraintRow->m_cfm = infoGlobal.m_globalCfm;
  1139. info2.cfm = &currentConstraintRow->m_cfm;
  1140. info2.m_lowerLimit = &currentConstraintRow->m_lowerLimit;
  1141. info2.m_upperLimit = &currentConstraintRow->m_upperLimit;
  1142. info2.m_numIterations = infoGlobal.m_numIterations;
  1143. constraints[i]->getInfo2(&info2);
  1144. ///finalize the constraint setup
  1145. for ( j=0;j<info1.m_numConstraintRows;j++)
  1146. {
  1147. btSolverConstraint& solverConstraint = currentConstraintRow[j];
  1148. solverConstraint.m_originalContactPoint = constraint;
  1149. solverConstraint.m_solverBodyIdA = idA;
  1150. solverConstraint.m_solverBodyIdB = idB;
  1151. {
  1152. const btVector3& ftorqueAxis1 = solverConstraint.m_relpos1CrossNormal;
  1153. solverConstraint.m_angularComponentA = constraint->getRigidBodyA().getInvInertiaTensorWorld()*ftorqueAxis1*constraint->getRigidBodyA().getAngularFactor();
  1154. }
  1155. {
  1156. const btVector3& ftorqueAxis2 = solverConstraint.m_relpos2CrossNormal;
  1157. solverConstraint.m_angularComponentB = constraint->getRigidBodyB().getInvInertiaTensorWorld()*ftorqueAxis2*constraint->getRigidBodyB().getAngularFactor();
  1158. }
  1159. {
  1160. btVector3 iMJlA = solverConstraint.m_contactNormal1*rbA.getInvMass();
  1161. btVector3 iMJaA = rbA.getInvInertiaTensorWorld()*solverConstraint.m_relpos1CrossNormal;
  1162. btVector3 iMJlB = solverConstraint.m_contactNormal2*rbB.getInvMass();//sign of normal?
  1163. btVector3 iMJaB = rbB.getInvInertiaTensorWorld()*solverConstraint.m_relpos2CrossNormal;
  1164. btScalar sum = iMJlA.dot(solverConstraint.m_contactNormal1);
  1165. sum += iMJaA.dot(solverConstraint.m_relpos1CrossNormal);
  1166. sum += iMJlB.dot(solverConstraint.m_contactNormal2);
  1167. sum += iMJaB.dot(solverConstraint.m_relpos2CrossNormal);
  1168. solverConstraint.m_jacDiagABInv = btScalar(1.)/sum;
  1169. }
  1170. ///fix rhs
  1171. ///todo: add force/torque accelerators
  1172. {
  1173. btScalar rel_vel;
  1174. btScalar vel1Dotn = solverConstraint.m_contactNormal1.dot(rbA.getLinearVelocity()) + solverConstraint.m_relpos1CrossNormal.dot(rbA.getAngularVelocity());
  1175. btScalar vel2Dotn = solverConstraint.m_contactNormal2.dot(rbB.getLinearVelocity()) + solverConstraint.m_relpos2CrossNormal.dot(rbB.getAngularVelocity());
  1176. rel_vel = vel1Dotn+vel2Dotn;
  1177. btScalar restitution = 0.f;
  1178. btScalar positionalError = solverConstraint.m_rhs;//already filled in by getConstraintInfo2
  1179. btScalar velocityError = restitution - rel_vel;// * damping;
  1180. btScalar penetrationImpulse = positionalError*solverConstraint.m_jacDiagABInv;
  1181. btScalar velocityImpulse = velocityError *solverConstraint.m_jacDiagABInv;
  1182. solverConstraint.m_rhs = penetrationImpulse+velocityImpulse;
  1183. solverConstraint.m_appliedImpulse = 0.f;
  1184. }
  1185. }
  1186. PfxConstraintPair& pair = jointPairs[actualNumJoints];
  1187. int numConstraintRows= info1.m_numConstraintRows;
  1188. pfxSetNumConstraints(pair,numConstraintRows);
  1189. pfxSetRigidBodyIdA(pair,idA);
  1190. pfxSetRigidBodyIdB(pair,idB);
  1191. //is this needed?
  1192. if (idA>=0)
  1193. pfxSetMotionMaskA(pair,m_memoryCache->m_mystates[idA].getMotionMask());
  1194. if (idB>=0)
  1195. pfxSetMotionMaskB(pair,m_memoryCache->m_mystates[idB].getMotionMask());
  1196. pfxSetActive(pair,true);
  1197. int id = currentConstraintRow-offsetSolverConstraints;
  1198. pfxSetContactId(pair,id);
  1199. actualNumJoints++;
  1200. }
  1201. currentRow+=m_tmpConstraintSizesPool[i].m_numConstraintRows;
  1202. }
  1203. }
  1204. }
  1205. float separateBias=0.1;//info.m_erp;//or m_erp2?
  1206. float timeStep=infoGlobal.m_timeStep;
  1207. int iteration=infoGlobal.m_numIterations;
  1208. //create a pair for each constraints, copy over info etc
  1209. {
  1210. BT_PROFILE("compute num contacts");
  1211. int totalContacts =0;
  1212. for (int i=0;i<actualNumManifolds;i++)
  1213. {
  1214. PfxConstraintPair* pair = &m_memoryCache->m_mypairs[i];
  1215. totalContacts += pfxGetNumConstraints(*pair);
  1216. }
  1217. //printf("numManifolds = %d\n",numManifolds);
  1218. //printf("totalContacts=%d\n",totalContacts);
  1219. }
  1220. // printf("actualNumManifolds=%d\n",actualNumManifolds);
  1221. {
  1222. BT_PROFILE("BPE_customConstraintSolverSequentialNew");
  1223. if (numRigidBodies>0 && (actualNumManifolds+actualNumJoints)>0)
  1224. {
  1225. // PFX_PRINTF("num points = %d\n",totalPoints);
  1226. // PFX_PRINTF("num points PFX = %d\n",total);
  1227. PfxConstraintRow* contactRows = actualNumManifolds? &m_memoryCache->m_constraintRows[0] : 0;
  1228. PfxBroadphasePair* actualPairs = m_memoryCache->m_mypairs.size() ? &m_memoryCache->m_mypairs[0] : 0;
  1229. BPE_customConstraintSolverSequentialNew(
  1230. actualNumManifolds,
  1231. actualPairs,
  1232. offsetContactManifolds,
  1233. contactRows,
  1234. &m_memoryCache->m_mystates[0],numRigidBodies,
  1235. &m_memoryCache->m_mysolverbodies[0],
  1236. jointPairs,actualNumJoints,
  1237. offsetSolverConstraints,
  1238. separateBias,timeStep,iteration,
  1239. m_solverThreadSupport,m_criticalSection,m_solverIO,m_barrier);
  1240. }
  1241. }
  1242. //copy results back to bodies
  1243. {
  1244. BT_PROFILE("copy back");
  1245. for (int i=0;i<numRigidBodies;i++)
  1246. {
  1247. btCollisionObject* obj = bodies1[i];
  1248. btRigidBody* rb = btRigidBody::upcast(obj);
  1249. TrbState& state = m_memoryCache->m_mystates[i];
  1250. if (rb && (rb->getInvMass()>0.f))
  1251. {
  1252. rb->setLinearVelocity(btVector3(state.getLinearVelocity().getX(),state.getLinearVelocity().getY(),state.getLinearVelocity().getZ()));
  1253. rb->setAngularVelocity(btVector3(state.getAngularVelocity().getX(),state.getAngularVelocity().getY(),state.getAngularVelocity().getZ()));
  1254. }
  1255. }
  1256. }
  1257. return 0.f;
  1258. }