btHingeConstraint.cpp 32 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046
  1. /*
  2. Bullet Continuous Collision Detection and Physics Library
  3. Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
  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 "btHingeConstraint.h"
  14. #include "bullet/BulletDynamics/Dynamics/btRigidBody.h"
  15. #include "bullet/LinearMath/btTransformUtil.h"
  16. #include "bullet/LinearMath/btMinMax.h"
  17. #include <new>
  18. #include "btSolverBody.h"
  19. //#define HINGE_USE_OBSOLETE_SOLVER false
  20. #define HINGE_USE_OBSOLETE_SOLVER false
  21. #define HINGE_USE_FRAME_OFFSET true
  22. #ifndef __SPU__
  23. btHingeConstraint::btHingeConstraint(btRigidBody& rbA,btRigidBody& rbB, const btVector3& pivotInA,const btVector3& pivotInB,
  24. const btVector3& axisInA,const btVector3& axisInB, bool useReferenceFrameA)
  25. :btTypedConstraint(HINGE_CONSTRAINT_TYPE, rbA,rbB),
  26. #ifdef _BT_USE_CENTER_LIMIT_
  27. m_limit(),
  28. #endif
  29. m_angularOnly(false),
  30. m_enableAngularMotor(false),
  31. m_useSolveConstraintObsolete(HINGE_USE_OBSOLETE_SOLVER),
  32. m_useOffsetForConstraintFrame(HINGE_USE_FRAME_OFFSET),
  33. m_useReferenceFrameA(useReferenceFrameA),
  34. m_flags(0)
  35. {
  36. m_rbAFrame.getOrigin() = pivotInA;
  37. // since no frame is given, assume this to be zero angle and just pick rb transform axis
  38. btVector3 rbAxisA1 = rbA.getCenterOfMassTransform().getBasis().getColumn(0);
  39. btVector3 rbAxisA2;
  40. btScalar projection = axisInA.dot(rbAxisA1);
  41. if (projection >= 1.0f - SIMD_EPSILON) {
  42. rbAxisA1 = -rbA.getCenterOfMassTransform().getBasis().getColumn(2);
  43. rbAxisA2 = rbA.getCenterOfMassTransform().getBasis().getColumn(1);
  44. } else if (projection <= -1.0f + SIMD_EPSILON) {
  45. rbAxisA1 = rbA.getCenterOfMassTransform().getBasis().getColumn(2);
  46. rbAxisA2 = rbA.getCenterOfMassTransform().getBasis().getColumn(1);
  47. } else {
  48. rbAxisA2 = axisInA.cross(rbAxisA1);
  49. rbAxisA1 = rbAxisA2.cross(axisInA);
  50. }
  51. m_rbAFrame.getBasis().setValue( rbAxisA1.getX(),rbAxisA2.getX(),axisInA.getX(),
  52. rbAxisA1.getY(),rbAxisA2.getY(),axisInA.getY(),
  53. rbAxisA1.getZ(),rbAxisA2.getZ(),axisInA.getZ() );
  54. btQuaternion rotationArc = shortestArcQuat(axisInA,axisInB);
  55. btVector3 rbAxisB1 = quatRotate(rotationArc,rbAxisA1);
  56. btVector3 rbAxisB2 = axisInB.cross(rbAxisB1);
  57. m_rbBFrame.getOrigin() = pivotInB;
  58. m_rbBFrame.getBasis().setValue( rbAxisB1.getX(),rbAxisB2.getX(),axisInB.getX(),
  59. rbAxisB1.getY(),rbAxisB2.getY(),axisInB.getY(),
  60. rbAxisB1.getZ(),rbAxisB2.getZ(),axisInB.getZ() );
  61. #ifndef _BT_USE_CENTER_LIMIT_
  62. //start with free
  63. m_lowerLimit = btScalar(1.0f);
  64. m_upperLimit = btScalar(-1.0f);
  65. m_biasFactor = 0.3f;
  66. m_relaxationFactor = 1.0f;
  67. m_limitSoftness = 0.9f;
  68. m_solveLimit = false;
  69. #endif
  70. m_referenceSign = m_useReferenceFrameA ? btScalar(-1.f) : btScalar(1.f);
  71. }
  72. btHingeConstraint::btHingeConstraint(btRigidBody& rbA,const btVector3& pivotInA,const btVector3& axisInA, bool useReferenceFrameA)
  73. :btTypedConstraint(HINGE_CONSTRAINT_TYPE, rbA),
  74. #ifdef _BT_USE_CENTER_LIMIT_
  75. m_limit(),
  76. #endif
  77. m_angularOnly(false), m_enableAngularMotor(false),
  78. m_useSolveConstraintObsolete(HINGE_USE_OBSOLETE_SOLVER),
  79. m_useOffsetForConstraintFrame(HINGE_USE_FRAME_OFFSET),
  80. m_useReferenceFrameA(useReferenceFrameA),
  81. m_flags(0)
  82. {
  83. // since no frame is given, assume this to be zero angle and just pick rb transform axis
  84. // fixed axis in worldspace
  85. btVector3 rbAxisA1, rbAxisA2;
  86. btPlaneSpace1(axisInA, rbAxisA1, rbAxisA2);
  87. m_rbAFrame.getOrigin() = pivotInA;
  88. m_rbAFrame.getBasis().setValue( rbAxisA1.getX(),rbAxisA2.getX(),axisInA.getX(),
  89. rbAxisA1.getY(),rbAxisA2.getY(),axisInA.getY(),
  90. rbAxisA1.getZ(),rbAxisA2.getZ(),axisInA.getZ() );
  91. btVector3 axisInB = rbA.getCenterOfMassTransform().getBasis() * axisInA;
  92. btQuaternion rotationArc = shortestArcQuat(axisInA,axisInB);
  93. btVector3 rbAxisB1 = quatRotate(rotationArc,rbAxisA1);
  94. btVector3 rbAxisB2 = axisInB.cross(rbAxisB1);
  95. m_rbBFrame.getOrigin() = rbA.getCenterOfMassTransform()(pivotInA);
  96. m_rbBFrame.getBasis().setValue( rbAxisB1.getX(),rbAxisB2.getX(),axisInB.getX(),
  97. rbAxisB1.getY(),rbAxisB2.getY(),axisInB.getY(),
  98. rbAxisB1.getZ(),rbAxisB2.getZ(),axisInB.getZ() );
  99. #ifndef _BT_USE_CENTER_LIMIT_
  100. //start with free
  101. m_lowerLimit = btScalar(1.0f);
  102. m_upperLimit = btScalar(-1.0f);
  103. m_biasFactor = 0.3f;
  104. m_relaxationFactor = 1.0f;
  105. m_limitSoftness = 0.9f;
  106. m_solveLimit = false;
  107. #endif
  108. m_referenceSign = m_useReferenceFrameA ? btScalar(-1.f) : btScalar(1.f);
  109. }
  110. btHingeConstraint::btHingeConstraint(btRigidBody& rbA,btRigidBody& rbB,
  111. const btTransform& rbAFrame, const btTransform& rbBFrame, bool useReferenceFrameA)
  112. :btTypedConstraint(HINGE_CONSTRAINT_TYPE, rbA,rbB),m_rbAFrame(rbAFrame),m_rbBFrame(rbBFrame),
  113. #ifdef _BT_USE_CENTER_LIMIT_
  114. m_limit(),
  115. #endif
  116. m_angularOnly(false),
  117. m_enableAngularMotor(false),
  118. m_useSolveConstraintObsolete(HINGE_USE_OBSOLETE_SOLVER),
  119. m_useOffsetForConstraintFrame(HINGE_USE_FRAME_OFFSET),
  120. m_useReferenceFrameA(useReferenceFrameA),
  121. m_flags(0)
  122. {
  123. #ifndef _BT_USE_CENTER_LIMIT_
  124. //start with free
  125. m_lowerLimit = btScalar(1.0f);
  126. m_upperLimit = btScalar(-1.0f);
  127. m_biasFactor = 0.3f;
  128. m_relaxationFactor = 1.0f;
  129. m_limitSoftness = 0.9f;
  130. m_solveLimit = false;
  131. #endif
  132. m_referenceSign = m_useReferenceFrameA ? btScalar(-1.f) : btScalar(1.f);
  133. }
  134. btHingeConstraint::btHingeConstraint(btRigidBody& rbA, const btTransform& rbAFrame, bool useReferenceFrameA)
  135. :btTypedConstraint(HINGE_CONSTRAINT_TYPE, rbA),m_rbAFrame(rbAFrame),m_rbBFrame(rbAFrame),
  136. #ifdef _BT_USE_CENTER_LIMIT_
  137. m_limit(),
  138. #endif
  139. m_angularOnly(false),
  140. m_enableAngularMotor(false),
  141. m_useSolveConstraintObsolete(HINGE_USE_OBSOLETE_SOLVER),
  142. m_useOffsetForConstraintFrame(HINGE_USE_FRAME_OFFSET),
  143. m_useReferenceFrameA(useReferenceFrameA),
  144. m_flags(0)
  145. {
  146. ///not providing rigidbody B means implicitly using worldspace for body B
  147. m_rbBFrame.getOrigin() = m_rbA.getCenterOfMassTransform()(m_rbAFrame.getOrigin());
  148. #ifndef _BT_USE_CENTER_LIMIT_
  149. //start with free
  150. m_lowerLimit = btScalar(1.0f);
  151. m_upperLimit = btScalar(-1.0f);
  152. m_biasFactor = 0.3f;
  153. m_relaxationFactor = 1.0f;
  154. m_limitSoftness = 0.9f;
  155. m_solveLimit = false;
  156. #endif
  157. m_referenceSign = m_useReferenceFrameA ? btScalar(-1.f) : btScalar(1.f);
  158. }
  159. void btHingeConstraint::buildJacobian()
  160. {
  161. if (m_useSolveConstraintObsolete)
  162. {
  163. m_appliedImpulse = btScalar(0.);
  164. m_accMotorImpulse = btScalar(0.);
  165. if (!m_angularOnly)
  166. {
  167. btVector3 pivotAInW = m_rbA.getCenterOfMassTransform()*m_rbAFrame.getOrigin();
  168. btVector3 pivotBInW = m_rbB.getCenterOfMassTransform()*m_rbBFrame.getOrigin();
  169. btVector3 relPos = pivotBInW - pivotAInW;
  170. btVector3 normal[3];
  171. if (relPos.length2() > SIMD_EPSILON)
  172. {
  173. normal[0] = relPos.normalized();
  174. }
  175. else
  176. {
  177. normal[0].setValue(btScalar(1.0),0,0);
  178. }
  179. btPlaneSpace1(normal[0], normal[1], normal[2]);
  180. for (int i=0;i<3;i++)
  181. {
  182. new (&m_jac[i]) btJacobianEntry(
  183. m_rbA.getCenterOfMassTransform().getBasis().transpose(),
  184. m_rbB.getCenterOfMassTransform().getBasis().transpose(),
  185. pivotAInW - m_rbA.getCenterOfMassPosition(),
  186. pivotBInW - m_rbB.getCenterOfMassPosition(),
  187. normal[i],
  188. m_rbA.getInvInertiaDiagLocal(),
  189. m_rbA.getInvMass(),
  190. m_rbB.getInvInertiaDiagLocal(),
  191. m_rbB.getInvMass());
  192. }
  193. }
  194. //calculate two perpendicular jointAxis, orthogonal to hingeAxis
  195. //these two jointAxis require equal angular velocities for both bodies
  196. //this is unused for now, it's a todo
  197. btVector3 jointAxis0local;
  198. btVector3 jointAxis1local;
  199. btPlaneSpace1(m_rbAFrame.getBasis().getColumn(2),jointAxis0local,jointAxis1local);
  200. btVector3 jointAxis0 = getRigidBodyA().getCenterOfMassTransform().getBasis() * jointAxis0local;
  201. btVector3 jointAxis1 = getRigidBodyA().getCenterOfMassTransform().getBasis() * jointAxis1local;
  202. btVector3 hingeAxisWorld = getRigidBodyA().getCenterOfMassTransform().getBasis() * m_rbAFrame.getBasis().getColumn(2);
  203. new (&m_jacAng[0]) btJacobianEntry(jointAxis0,
  204. m_rbA.getCenterOfMassTransform().getBasis().transpose(),
  205. m_rbB.getCenterOfMassTransform().getBasis().transpose(),
  206. m_rbA.getInvInertiaDiagLocal(),
  207. m_rbB.getInvInertiaDiagLocal());
  208. new (&m_jacAng[1]) btJacobianEntry(jointAxis1,
  209. m_rbA.getCenterOfMassTransform().getBasis().transpose(),
  210. m_rbB.getCenterOfMassTransform().getBasis().transpose(),
  211. m_rbA.getInvInertiaDiagLocal(),
  212. m_rbB.getInvInertiaDiagLocal());
  213. new (&m_jacAng[2]) btJacobianEntry(hingeAxisWorld,
  214. m_rbA.getCenterOfMassTransform().getBasis().transpose(),
  215. m_rbB.getCenterOfMassTransform().getBasis().transpose(),
  216. m_rbA.getInvInertiaDiagLocal(),
  217. m_rbB.getInvInertiaDiagLocal());
  218. // clear accumulator
  219. m_accLimitImpulse = btScalar(0.);
  220. // test angular limit
  221. testLimit(m_rbA.getCenterOfMassTransform(),m_rbB.getCenterOfMassTransform());
  222. //Compute K = J*W*J' for hinge axis
  223. btVector3 axisA = getRigidBodyA().getCenterOfMassTransform().getBasis() * m_rbAFrame.getBasis().getColumn(2);
  224. m_kHinge = 1.0f / (getRigidBodyA().computeAngularImpulseDenominator(axisA) +
  225. getRigidBodyB().computeAngularImpulseDenominator(axisA));
  226. }
  227. }
  228. #endif //__SPU__
  229. void btHingeConstraint::getInfo1(btConstraintInfo1* info)
  230. {
  231. if (m_useSolveConstraintObsolete)
  232. {
  233. info->m_numConstraintRows = 0;
  234. info->nub = 0;
  235. }
  236. else
  237. {
  238. info->m_numConstraintRows = 5; // Fixed 3 linear + 2 angular
  239. info->nub = 1;
  240. //always add the row, to avoid computation (data is not available yet)
  241. //prepare constraint
  242. testLimit(m_rbA.getCenterOfMassTransform(),m_rbB.getCenterOfMassTransform());
  243. if(getSolveLimit() || getEnableAngularMotor())
  244. {
  245. info->m_numConstraintRows++; // limit 3rd anguar as well
  246. info->nub--;
  247. }
  248. }
  249. }
  250. void btHingeConstraint::getInfo1NonVirtual(btConstraintInfo1* info)
  251. {
  252. if (m_useSolveConstraintObsolete)
  253. {
  254. info->m_numConstraintRows = 0;
  255. info->nub = 0;
  256. }
  257. else
  258. {
  259. //always add the 'limit' row, to avoid computation (data is not available yet)
  260. info->m_numConstraintRows = 6; // Fixed 3 linear + 2 angular
  261. info->nub = 0;
  262. }
  263. }
  264. void btHingeConstraint::getInfo2 (btConstraintInfo2* info)
  265. {
  266. if(m_useOffsetForConstraintFrame)
  267. {
  268. getInfo2InternalUsingFrameOffset(info, m_rbA.getCenterOfMassTransform(),m_rbB.getCenterOfMassTransform(),m_rbA.getAngularVelocity(),m_rbB.getAngularVelocity());
  269. }
  270. else
  271. {
  272. getInfo2Internal(info, m_rbA.getCenterOfMassTransform(),m_rbB.getCenterOfMassTransform(),m_rbA.getAngularVelocity(),m_rbB.getAngularVelocity());
  273. }
  274. }
  275. void btHingeConstraint::getInfo2NonVirtual (btConstraintInfo2* info,const btTransform& transA,const btTransform& transB,const btVector3& angVelA,const btVector3& angVelB)
  276. {
  277. ///the regular (virtual) implementation getInfo2 already performs 'testLimit' during getInfo1, so we need to do it now
  278. testLimit(transA,transB);
  279. getInfo2Internal(info,transA,transB,angVelA,angVelB);
  280. }
  281. void btHingeConstraint::getInfo2Internal(btConstraintInfo2* info, const btTransform& transA,const btTransform& transB,const btVector3& angVelA,const btVector3& angVelB)
  282. {
  283. btAssert(!m_useSolveConstraintObsolete);
  284. int i, skip = info->rowskip;
  285. // transforms in world space
  286. btTransform trA = transA*m_rbAFrame;
  287. btTransform trB = transB*m_rbBFrame;
  288. // pivot point
  289. btVector3 pivotAInW = trA.getOrigin();
  290. btVector3 pivotBInW = trB.getOrigin();
  291. #if 0
  292. if (0)
  293. {
  294. for (i=0;i<6;i++)
  295. {
  296. info->m_J1linearAxis[i*skip]=0;
  297. info->m_J1linearAxis[i*skip+1]=0;
  298. info->m_J1linearAxis[i*skip+2]=0;
  299. info->m_J1angularAxis[i*skip]=0;
  300. info->m_J1angularAxis[i*skip+1]=0;
  301. info->m_J1angularAxis[i*skip+2]=0;
  302. info->m_J2linearAxis[i*skip]=0;
  303. info->m_J2linearAxis[i*skip+1]=0;
  304. info->m_J2linearAxis[i*skip+2]=0;
  305. info->m_J2angularAxis[i*skip]=0;
  306. info->m_J2angularAxis[i*skip+1]=0;
  307. info->m_J2angularAxis[i*skip+2]=0;
  308. info->m_constraintError[i*skip]=0.f;
  309. }
  310. }
  311. #endif //#if 0
  312. // linear (all fixed)
  313. if (!m_angularOnly)
  314. {
  315. info->m_J1linearAxis[0] = 1;
  316. info->m_J1linearAxis[skip + 1] = 1;
  317. info->m_J1linearAxis[2 * skip + 2] = 1;
  318. info->m_J2linearAxis[0] = -1;
  319. info->m_J2linearAxis[skip + 1] = -1;
  320. info->m_J2linearAxis[2 * skip + 2] = -1;
  321. }
  322. btVector3 a1 = pivotAInW - transA.getOrigin();
  323. {
  324. btVector3* angular0 = (btVector3*)(info->m_J1angularAxis);
  325. btVector3* angular1 = (btVector3*)(info->m_J1angularAxis + skip);
  326. btVector3* angular2 = (btVector3*)(info->m_J1angularAxis + 2 * skip);
  327. btVector3 a1neg = -a1;
  328. a1neg.getSkewSymmetricMatrix(angular0,angular1,angular2);
  329. }
  330. btVector3 a2 = pivotBInW - transB.getOrigin();
  331. {
  332. btVector3* angular0 = (btVector3*)(info->m_J2angularAxis);
  333. btVector3* angular1 = (btVector3*)(info->m_J2angularAxis + skip);
  334. btVector3* angular2 = (btVector3*)(info->m_J2angularAxis + 2 * skip);
  335. a2.getSkewSymmetricMatrix(angular0,angular1,angular2);
  336. }
  337. // linear RHS
  338. btScalar k = info->fps * info->erp;
  339. if (!m_angularOnly)
  340. {
  341. for(i = 0; i < 3; i++)
  342. {
  343. info->m_constraintError[i * skip] = k * (pivotBInW[i] - pivotAInW[i]);
  344. }
  345. }
  346. // make rotations around X and Y equal
  347. // the hinge axis should be the only unconstrained
  348. // rotational axis, the angular velocity of the two bodies perpendicular to
  349. // the hinge axis should be equal. thus the constraint equations are
  350. // p*w1 - p*w2 = 0
  351. // q*w1 - q*w2 = 0
  352. // where p and q are unit vectors normal to the hinge axis, and w1 and w2
  353. // are the angular velocity vectors of the two bodies.
  354. // get hinge axis (Z)
  355. btVector3 ax1 = trA.getBasis().getColumn(2);
  356. // get 2 orthos to hinge axis (X, Y)
  357. btVector3 p = trA.getBasis().getColumn(0);
  358. btVector3 q = trA.getBasis().getColumn(1);
  359. // set the two hinge angular rows
  360. int s3 = 3 * info->rowskip;
  361. int s4 = 4 * info->rowskip;
  362. info->m_J1angularAxis[s3 + 0] = p[0];
  363. info->m_J1angularAxis[s3 + 1] = p[1];
  364. info->m_J1angularAxis[s3 + 2] = p[2];
  365. info->m_J1angularAxis[s4 + 0] = q[0];
  366. info->m_J1angularAxis[s4 + 1] = q[1];
  367. info->m_J1angularAxis[s4 + 2] = q[2];
  368. info->m_J2angularAxis[s3 + 0] = -p[0];
  369. info->m_J2angularAxis[s3 + 1] = -p[1];
  370. info->m_J2angularAxis[s3 + 2] = -p[2];
  371. info->m_J2angularAxis[s4 + 0] = -q[0];
  372. info->m_J2angularAxis[s4 + 1] = -q[1];
  373. info->m_J2angularAxis[s4 + 2] = -q[2];
  374. // compute the right hand side of the constraint equation. set relative
  375. // body velocities along p and q to bring the hinge back into alignment.
  376. // if ax1,ax2 are the unit length hinge axes as computed from body1 and
  377. // body2, we need to rotate both bodies along the axis u = (ax1 x ax2).
  378. // if `theta' is the angle between ax1 and ax2, we need an angular velocity
  379. // along u to cover angle erp*theta in one step :
  380. // |angular_velocity| = angle/time = erp*theta / stepsize
  381. // = (erp*fps) * theta
  382. // angular_velocity = |angular_velocity| * (ax1 x ax2) / |ax1 x ax2|
  383. // = (erp*fps) * theta * (ax1 x ax2) / sin(theta)
  384. // ...as ax1 and ax2 are unit length. if theta is smallish,
  385. // theta ~= sin(theta), so
  386. // angular_velocity = (erp*fps) * (ax1 x ax2)
  387. // ax1 x ax2 is in the plane space of ax1, so we project the angular
  388. // velocity to p and q to find the right hand side.
  389. btVector3 ax2 = trB.getBasis().getColumn(2);
  390. btVector3 u = ax1.cross(ax2);
  391. info->m_constraintError[s3] = k * u.dot(p);
  392. info->m_constraintError[s4] = k * u.dot(q);
  393. // check angular limits
  394. int nrow = 4; // last filled row
  395. int srow;
  396. btScalar limit_err = btScalar(0.0);
  397. int limit = 0;
  398. if(getSolveLimit())
  399. {
  400. #ifdef _BT_USE_CENTER_LIMIT_
  401. limit_err = m_limit.getCorrection() * m_referenceSign;
  402. #else
  403. limit_err = m_correction * m_referenceSign;
  404. #endif
  405. limit = (limit_err > btScalar(0.0)) ? 1 : 2;
  406. }
  407. // if the hinge has joint limits or motor, add in the extra row
  408. int powered = 0;
  409. if(getEnableAngularMotor())
  410. {
  411. powered = 1;
  412. }
  413. if(limit || powered)
  414. {
  415. nrow++;
  416. srow = nrow * info->rowskip;
  417. info->m_J1angularAxis[srow+0] = ax1[0];
  418. info->m_J1angularAxis[srow+1] = ax1[1];
  419. info->m_J1angularAxis[srow+2] = ax1[2];
  420. info->m_J2angularAxis[srow+0] = -ax1[0];
  421. info->m_J2angularAxis[srow+1] = -ax1[1];
  422. info->m_J2angularAxis[srow+2] = -ax1[2];
  423. btScalar lostop = getLowerLimit();
  424. btScalar histop = getUpperLimit();
  425. if(limit && (lostop == histop))
  426. { // the joint motor is ineffective
  427. powered = 0;
  428. }
  429. info->m_constraintError[srow] = btScalar(0.0f);
  430. btScalar currERP = (m_flags & BT_HINGE_FLAGS_ERP_STOP) ? m_stopERP : info->erp;
  431. if(powered)
  432. {
  433. if(m_flags & BT_HINGE_FLAGS_CFM_NORM)
  434. {
  435. info->cfm[srow] = m_normalCFM;
  436. }
  437. btScalar mot_fact = getMotorFactor(m_hingeAngle, lostop, histop, m_motorTargetVelocity, info->fps * currERP);
  438. info->m_constraintError[srow] += mot_fact * m_motorTargetVelocity * m_referenceSign;
  439. info->m_lowerLimit[srow] = - m_maxMotorImpulse;
  440. info->m_upperLimit[srow] = m_maxMotorImpulse;
  441. }
  442. if(limit)
  443. {
  444. k = info->fps * currERP;
  445. info->m_constraintError[srow] += k * limit_err;
  446. if(m_flags & BT_HINGE_FLAGS_CFM_STOP)
  447. {
  448. info->cfm[srow] = m_stopCFM;
  449. }
  450. if(lostop == histop)
  451. {
  452. // limited low and high simultaneously
  453. info->m_lowerLimit[srow] = -SIMD_INFINITY;
  454. info->m_upperLimit[srow] = SIMD_INFINITY;
  455. }
  456. else if(limit == 1)
  457. { // low limit
  458. info->m_lowerLimit[srow] = 0;
  459. info->m_upperLimit[srow] = SIMD_INFINITY;
  460. }
  461. else
  462. { // high limit
  463. info->m_lowerLimit[srow] = -SIMD_INFINITY;
  464. info->m_upperLimit[srow] = 0;
  465. }
  466. // bounce (we'll use slider parameter abs(1.0 - m_dampingLimAng) for that)
  467. #ifdef _BT_USE_CENTER_LIMIT_
  468. btScalar bounce = m_limit.getRelaxationFactor();
  469. #else
  470. btScalar bounce = m_relaxationFactor;
  471. #endif
  472. if(bounce > btScalar(0.0))
  473. {
  474. btScalar vel = angVelA.dot(ax1);
  475. vel -= angVelB.dot(ax1);
  476. // only apply bounce if the velocity is incoming, and if the
  477. // resulting c[] exceeds what we already have.
  478. if(limit == 1)
  479. { // low limit
  480. if(vel < 0)
  481. {
  482. btScalar newc = -bounce * vel;
  483. if(newc > info->m_constraintError[srow])
  484. {
  485. info->m_constraintError[srow] = newc;
  486. }
  487. }
  488. }
  489. else
  490. { // high limit - all those computations are reversed
  491. if(vel > 0)
  492. {
  493. btScalar newc = -bounce * vel;
  494. if(newc < info->m_constraintError[srow])
  495. {
  496. info->m_constraintError[srow] = newc;
  497. }
  498. }
  499. }
  500. }
  501. #ifdef _BT_USE_CENTER_LIMIT_
  502. info->m_constraintError[srow] *= m_limit.getBiasFactor();
  503. #else
  504. info->m_constraintError[srow] *= m_biasFactor;
  505. #endif
  506. } // if(limit)
  507. } // if angular limit or powered
  508. }
  509. void btHingeConstraint::setFrames(const btTransform & frameA, const btTransform & frameB)
  510. {
  511. m_rbAFrame = frameA;
  512. m_rbBFrame = frameB;
  513. buildJacobian();
  514. }
  515. void btHingeConstraint::updateRHS(btScalar timeStep)
  516. {
  517. (void)timeStep;
  518. }
  519. btScalar btHingeConstraint::getHingeAngle()
  520. {
  521. return getHingeAngle(m_rbA.getCenterOfMassTransform(),m_rbB.getCenterOfMassTransform());
  522. }
  523. btScalar btHingeConstraint::getHingeAngle(const btTransform& transA,const btTransform& transB)
  524. {
  525. const btVector3 refAxis0 = transA.getBasis() * m_rbAFrame.getBasis().getColumn(0);
  526. const btVector3 refAxis1 = transA.getBasis() * m_rbAFrame.getBasis().getColumn(1);
  527. const btVector3 swingAxis = transB.getBasis() * m_rbBFrame.getBasis().getColumn(1);
  528. // btScalar angle = btAtan2Fast(swingAxis.dot(refAxis0), swingAxis.dot(refAxis1));
  529. btScalar angle = btAtan2(swingAxis.dot(refAxis0), swingAxis.dot(refAxis1));
  530. return m_referenceSign * angle;
  531. }
  532. void btHingeConstraint::testLimit(const btTransform& transA,const btTransform& transB)
  533. {
  534. // Compute limit information
  535. m_hingeAngle = getHingeAngle(transA,transB);
  536. #ifdef _BT_USE_CENTER_LIMIT_
  537. m_limit.test(m_hingeAngle);
  538. #else
  539. m_correction = btScalar(0.);
  540. m_limitSign = btScalar(0.);
  541. m_solveLimit = false;
  542. if (m_lowerLimit <= m_upperLimit)
  543. {
  544. m_hingeAngle = btAdjustAngleToLimits(m_hingeAngle, m_lowerLimit, m_upperLimit);
  545. if (m_hingeAngle <= m_lowerLimit)
  546. {
  547. m_correction = (m_lowerLimit - m_hingeAngle);
  548. m_limitSign = 1.0f;
  549. m_solveLimit = true;
  550. }
  551. else if (m_hingeAngle >= m_upperLimit)
  552. {
  553. m_correction = m_upperLimit - m_hingeAngle;
  554. m_limitSign = -1.0f;
  555. m_solveLimit = true;
  556. }
  557. }
  558. #endif
  559. return;
  560. }
  561. static btVector3 vHinge(0, 0, btScalar(1));
  562. void btHingeConstraint::setMotorTarget(const btQuaternion& qAinB, btScalar dt)
  563. {
  564. // convert target from body to constraint space
  565. btQuaternion qConstraint = m_rbBFrame.getRotation().inverse() * qAinB * m_rbAFrame.getRotation();
  566. qConstraint.normalize();
  567. // extract "pure" hinge component
  568. btVector3 vNoHinge = quatRotate(qConstraint, vHinge); vNoHinge.normalize();
  569. btQuaternion qNoHinge = shortestArcQuat(vHinge, vNoHinge);
  570. btQuaternion qHinge = qNoHinge.inverse() * qConstraint;
  571. qHinge.normalize();
  572. // compute angular target, clamped to limits
  573. btScalar targetAngle = qHinge.getAngle();
  574. if (targetAngle > SIMD_PI) // long way around. flip quat and recalculate.
  575. {
  576. qHinge = -(qHinge);
  577. targetAngle = qHinge.getAngle();
  578. }
  579. if (qHinge.getZ() < 0)
  580. targetAngle = -targetAngle;
  581. setMotorTarget(targetAngle, dt);
  582. }
  583. void btHingeConstraint::setMotorTarget(btScalar targetAngle, btScalar dt)
  584. {
  585. #ifdef _BT_USE_CENTER_LIMIT_
  586. m_limit.fit(targetAngle);
  587. #else
  588. if (m_lowerLimit < m_upperLimit)
  589. {
  590. if (targetAngle < m_lowerLimit)
  591. targetAngle = m_lowerLimit;
  592. else if (targetAngle > m_upperLimit)
  593. targetAngle = m_upperLimit;
  594. }
  595. #endif
  596. // compute angular velocity
  597. btScalar curAngle = getHingeAngle(m_rbA.getCenterOfMassTransform(),m_rbB.getCenterOfMassTransform());
  598. btScalar dAngle = targetAngle - curAngle;
  599. m_motorTargetVelocity = dAngle / dt;
  600. }
  601. void btHingeConstraint::getInfo2InternalUsingFrameOffset(btConstraintInfo2* info, const btTransform& transA,const btTransform& transB,const btVector3& angVelA,const btVector3& angVelB)
  602. {
  603. btAssert(!m_useSolveConstraintObsolete);
  604. int i, s = info->rowskip;
  605. // transforms in world space
  606. btTransform trA = transA*m_rbAFrame;
  607. btTransform trB = transB*m_rbBFrame;
  608. // pivot point
  609. // btVector3 pivotAInW = trA.getOrigin();
  610. // btVector3 pivotBInW = trB.getOrigin();
  611. #if 1
  612. // difference between frames in WCS
  613. btVector3 ofs = trB.getOrigin() - trA.getOrigin();
  614. // now get weight factors depending on masses
  615. btScalar miA = getRigidBodyA().getInvMass();
  616. btScalar miB = getRigidBodyB().getInvMass();
  617. bool hasStaticBody = (miA < SIMD_EPSILON) || (miB < SIMD_EPSILON);
  618. btScalar miS = miA + miB;
  619. btScalar factA, factB;
  620. if(miS > btScalar(0.f))
  621. {
  622. factA = miB / miS;
  623. }
  624. else
  625. {
  626. factA = btScalar(0.5f);
  627. }
  628. factB = btScalar(1.0f) - factA;
  629. // get the desired direction of hinge axis
  630. // as weighted sum of Z-orthos of frameA and frameB in WCS
  631. btVector3 ax1A = trA.getBasis().getColumn(2);
  632. btVector3 ax1B = trB.getBasis().getColumn(2);
  633. btVector3 ax1 = ax1A * factA + ax1B * factB;
  634. ax1.normalize();
  635. // fill first 3 rows
  636. // we want: velA + wA x relA == velB + wB x relB
  637. btTransform bodyA_trans = transA;
  638. btTransform bodyB_trans = transB;
  639. int s0 = 0;
  640. int s1 = s;
  641. int s2 = s * 2;
  642. int nrow = 2; // last filled row
  643. btVector3 tmpA, tmpB, relA, relB, p, q;
  644. // get vector from bodyB to frameB in WCS
  645. relB = trB.getOrigin() - bodyB_trans.getOrigin();
  646. // get its projection to hinge axis
  647. btVector3 projB = ax1 * relB.dot(ax1);
  648. // get vector directed from bodyB to hinge axis (and orthogonal to it)
  649. btVector3 orthoB = relB - projB;
  650. // same for bodyA
  651. relA = trA.getOrigin() - bodyA_trans.getOrigin();
  652. btVector3 projA = ax1 * relA.dot(ax1);
  653. btVector3 orthoA = relA - projA;
  654. btVector3 totalDist = projA - projB;
  655. // get offset vectors relA and relB
  656. relA = orthoA + totalDist * factA;
  657. relB = orthoB - totalDist * factB;
  658. // now choose average ortho to hinge axis
  659. p = orthoB * factA + orthoA * factB;
  660. btScalar len2 = p.length2();
  661. if(len2 > SIMD_EPSILON)
  662. {
  663. p /= btSqrt(len2);
  664. }
  665. else
  666. {
  667. p = trA.getBasis().getColumn(1);
  668. }
  669. // make one more ortho
  670. q = ax1.cross(p);
  671. // fill three rows
  672. tmpA = relA.cross(p);
  673. tmpB = relB.cross(p);
  674. for (i=0; i<3; i++) info->m_J1angularAxis[s0+i] = tmpA[i];
  675. for (i=0; i<3; i++) info->m_J2angularAxis[s0+i] = -tmpB[i];
  676. tmpA = relA.cross(q);
  677. tmpB = relB.cross(q);
  678. if(hasStaticBody && getSolveLimit())
  679. { // to make constraint between static and dynamic objects more rigid
  680. // remove wA (or wB) from equation if angular limit is hit
  681. tmpB *= factB;
  682. tmpA *= factA;
  683. }
  684. for (i=0; i<3; i++) info->m_J1angularAxis[s1+i] = tmpA[i];
  685. for (i=0; i<3; i++) info->m_J2angularAxis[s1+i] = -tmpB[i];
  686. tmpA = relA.cross(ax1);
  687. tmpB = relB.cross(ax1);
  688. if(hasStaticBody)
  689. { // to make constraint between static and dynamic objects more rigid
  690. // remove wA (or wB) from equation
  691. tmpB *= factB;
  692. tmpA *= factA;
  693. }
  694. for (i=0; i<3; i++) info->m_J1angularAxis[s2+i] = tmpA[i];
  695. for (i=0; i<3; i++) info->m_J2angularAxis[s2+i] = -tmpB[i];
  696. btScalar k = info->fps * info->erp;
  697. if (!m_angularOnly)
  698. {
  699. for (i=0; i<3; i++) info->m_J1linearAxis[s0+i] = p[i];
  700. for (i=0; i<3; i++) info->m_J1linearAxis[s1+i] = q[i];
  701. for (i=0; i<3; i++) info->m_J1linearAxis[s2+i] = ax1[i];
  702. for (i=0; i<3; i++) info->m_J2linearAxis[s0+i] = -p[i];
  703. for (i=0; i<3; i++) info->m_J2linearAxis[s1+i] = -q[i];
  704. for (i=0; i<3; i++) info->m_J2linearAxis[s2+i] = -ax1[i];
  705. // compute three elements of right hand side
  706. btScalar rhs = k * p.dot(ofs);
  707. info->m_constraintError[s0] = rhs;
  708. rhs = k * q.dot(ofs);
  709. info->m_constraintError[s1] = rhs;
  710. rhs = k * ax1.dot(ofs);
  711. info->m_constraintError[s2] = rhs;
  712. }
  713. // the hinge axis should be the only unconstrained
  714. // rotational axis, the angular velocity of the two bodies perpendicular to
  715. // the hinge axis should be equal. thus the constraint equations are
  716. // p*w1 - p*w2 = 0
  717. // q*w1 - q*w2 = 0
  718. // where p and q are unit vectors normal to the hinge axis, and w1 and w2
  719. // are the angular velocity vectors of the two bodies.
  720. int s3 = 3 * s;
  721. int s4 = 4 * s;
  722. info->m_J1angularAxis[s3 + 0] = p[0];
  723. info->m_J1angularAxis[s3 + 1] = p[1];
  724. info->m_J1angularAxis[s3 + 2] = p[2];
  725. info->m_J1angularAxis[s4 + 0] = q[0];
  726. info->m_J1angularAxis[s4 + 1] = q[1];
  727. info->m_J1angularAxis[s4 + 2] = q[2];
  728. info->m_J2angularAxis[s3 + 0] = -p[0];
  729. info->m_J2angularAxis[s3 + 1] = -p[1];
  730. info->m_J2angularAxis[s3 + 2] = -p[2];
  731. info->m_J2angularAxis[s4 + 0] = -q[0];
  732. info->m_J2angularAxis[s4 + 1] = -q[1];
  733. info->m_J2angularAxis[s4 + 2] = -q[2];
  734. // compute the right hand side of the constraint equation. set relative
  735. // body velocities along p and q to bring the hinge back into alignment.
  736. // if ax1A,ax1B are the unit length hinge axes as computed from bodyA and
  737. // bodyB, we need to rotate both bodies along the axis u = (ax1 x ax2).
  738. // if "theta" is the angle between ax1 and ax2, we need an angular velocity
  739. // along u to cover angle erp*theta in one step :
  740. // |angular_velocity| = angle/time = erp*theta / stepsize
  741. // = (erp*fps) * theta
  742. // angular_velocity = |angular_velocity| * (ax1 x ax2) / |ax1 x ax2|
  743. // = (erp*fps) * theta * (ax1 x ax2) / sin(theta)
  744. // ...as ax1 and ax2 are unit length. if theta is smallish,
  745. // theta ~= sin(theta), so
  746. // angular_velocity = (erp*fps) * (ax1 x ax2)
  747. // ax1 x ax2 is in the plane space of ax1, so we project the angular
  748. // velocity to p and q to find the right hand side.
  749. k = info->fps * info->erp;
  750. btVector3 u = ax1A.cross(ax1B);
  751. info->m_constraintError[s3] = k * u.dot(p);
  752. info->m_constraintError[s4] = k * u.dot(q);
  753. #endif
  754. // check angular limits
  755. nrow = 4; // last filled row
  756. int srow;
  757. btScalar limit_err = btScalar(0.0);
  758. int limit = 0;
  759. if(getSolveLimit())
  760. {
  761. #ifdef _BT_USE_CENTER_LIMIT_
  762. limit_err = m_limit.getCorrection() * m_referenceSign;
  763. #else
  764. limit_err = m_correction * m_referenceSign;
  765. #endif
  766. limit = (limit_err > btScalar(0.0)) ? 1 : 2;
  767. }
  768. // if the hinge has joint limits or motor, add in the extra row
  769. int powered = 0;
  770. if(getEnableAngularMotor())
  771. {
  772. powered = 1;
  773. }
  774. if(limit || powered)
  775. {
  776. nrow++;
  777. srow = nrow * info->rowskip;
  778. info->m_J1angularAxis[srow+0] = ax1[0];
  779. info->m_J1angularAxis[srow+1] = ax1[1];
  780. info->m_J1angularAxis[srow+2] = ax1[2];
  781. info->m_J2angularAxis[srow+0] = -ax1[0];
  782. info->m_J2angularAxis[srow+1] = -ax1[1];
  783. info->m_J2angularAxis[srow+2] = -ax1[2];
  784. btScalar lostop = getLowerLimit();
  785. btScalar histop = getUpperLimit();
  786. if(limit && (lostop == histop))
  787. { // the joint motor is ineffective
  788. powered = 0;
  789. }
  790. info->m_constraintError[srow] = btScalar(0.0f);
  791. btScalar currERP = (m_flags & BT_HINGE_FLAGS_ERP_STOP) ? m_stopERP : info->erp;
  792. if(powered)
  793. {
  794. if(m_flags & BT_HINGE_FLAGS_CFM_NORM)
  795. {
  796. info->cfm[srow] = m_normalCFM;
  797. }
  798. btScalar mot_fact = getMotorFactor(m_hingeAngle, lostop, histop, m_motorTargetVelocity, info->fps * currERP);
  799. info->m_constraintError[srow] += mot_fact * m_motorTargetVelocity * m_referenceSign;
  800. info->m_lowerLimit[srow] = - m_maxMotorImpulse;
  801. info->m_upperLimit[srow] = m_maxMotorImpulse;
  802. }
  803. if(limit)
  804. {
  805. k = info->fps * currERP;
  806. info->m_constraintError[srow] += k * limit_err;
  807. if(m_flags & BT_HINGE_FLAGS_CFM_STOP)
  808. {
  809. info->cfm[srow] = m_stopCFM;
  810. }
  811. if(lostop == histop)
  812. {
  813. // limited low and high simultaneously
  814. info->m_lowerLimit[srow] = -SIMD_INFINITY;
  815. info->m_upperLimit[srow] = SIMD_INFINITY;
  816. }
  817. else if(limit == 1)
  818. { // low limit
  819. info->m_lowerLimit[srow] = 0;
  820. info->m_upperLimit[srow] = SIMD_INFINITY;
  821. }
  822. else
  823. { // high limit
  824. info->m_lowerLimit[srow] = -SIMD_INFINITY;
  825. info->m_upperLimit[srow] = 0;
  826. }
  827. // bounce (we'll use slider parameter abs(1.0 - m_dampingLimAng) for that)
  828. #ifdef _BT_USE_CENTER_LIMIT_
  829. btScalar bounce = m_limit.getRelaxationFactor();
  830. #else
  831. btScalar bounce = m_relaxationFactor;
  832. #endif
  833. if(bounce > btScalar(0.0))
  834. {
  835. btScalar vel = angVelA.dot(ax1);
  836. vel -= angVelB.dot(ax1);
  837. // only apply bounce if the velocity is incoming, and if the
  838. // resulting c[] exceeds what we already have.
  839. if(limit == 1)
  840. { // low limit
  841. if(vel < 0)
  842. {
  843. btScalar newc = -bounce * vel;
  844. if(newc > info->m_constraintError[srow])
  845. {
  846. info->m_constraintError[srow] = newc;
  847. }
  848. }
  849. }
  850. else
  851. { // high limit - all those computations are reversed
  852. if(vel > 0)
  853. {
  854. btScalar newc = -bounce * vel;
  855. if(newc < info->m_constraintError[srow])
  856. {
  857. info->m_constraintError[srow] = newc;
  858. }
  859. }
  860. }
  861. }
  862. #ifdef _BT_USE_CENTER_LIMIT_
  863. info->m_constraintError[srow] *= m_limit.getBiasFactor();
  864. #else
  865. info->m_constraintError[srow] *= m_biasFactor;
  866. #endif
  867. } // if(limit)
  868. } // if angular limit or powered
  869. }
  870. ///override the default global value of a parameter (such as ERP or CFM), optionally provide the axis (0..5).
  871. ///If no axis is provided, it uses the default axis for this constraint.
  872. void btHingeConstraint::setParam(int num, btScalar value, int axis)
  873. {
  874. if((axis == -1) || (axis == 5))
  875. {
  876. switch(num)
  877. {
  878. case BT_CONSTRAINT_STOP_ERP :
  879. m_stopERP = value;
  880. m_flags |= BT_HINGE_FLAGS_ERP_STOP;
  881. break;
  882. case BT_CONSTRAINT_STOP_CFM :
  883. m_stopCFM = value;
  884. m_flags |= BT_HINGE_FLAGS_CFM_STOP;
  885. break;
  886. case BT_CONSTRAINT_CFM :
  887. m_normalCFM = value;
  888. m_flags |= BT_HINGE_FLAGS_CFM_NORM;
  889. break;
  890. default :
  891. btAssertConstrParams(0);
  892. }
  893. }
  894. else
  895. {
  896. btAssertConstrParams(0);
  897. }
  898. }
  899. ///return the local value of parameter
  900. btScalar btHingeConstraint::getParam(int num, int axis) const
  901. {
  902. btScalar retVal = 0;
  903. if((axis == -1) || (axis == 5))
  904. {
  905. switch(num)
  906. {
  907. case BT_CONSTRAINT_STOP_ERP :
  908. btAssertConstrParams(m_flags & BT_HINGE_FLAGS_ERP_STOP);
  909. retVal = m_stopERP;
  910. break;
  911. case BT_CONSTRAINT_STOP_CFM :
  912. btAssertConstrParams(m_flags & BT_HINGE_FLAGS_CFM_STOP);
  913. retVal = m_stopCFM;
  914. break;
  915. case BT_CONSTRAINT_CFM :
  916. btAssertConstrParams(m_flags & BT_HINGE_FLAGS_CFM_NORM);
  917. retVal = m_normalCFM;
  918. break;
  919. default :
  920. btAssertConstrParams(0);
  921. }
  922. }
  923. else
  924. {
  925. btAssertConstrParams(0);
  926. }
  927. return retVal;
  928. }