Bullet Collision Detection & Physics Library
btSliderConstraint.cpp
Go to the documentation of this file.
1 /*
2 Bullet Continuous Collision Detection and Physics Library
3 Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
4 
5 This software is provided 'as-is', without any express or implied warranty.
6 In no event will the authors be held liable for any damages arising from the use of this software.
7 Permission is granted to anyone to use this software for any purpose,
8 including commercial applications, and to alter it and redistribute it freely,
9 subject to the following restrictions:
10 
11 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.
12 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
13 3. This notice may not be removed or altered from any source distribution.
14 */
15 
16 /*
17 Added by Roman Ponomarev (rponom@gmail.com)
18 April 04, 2008
19 */
20 
21 
22 
23 #include "btSliderConstraint.h"
26 #include <new>
27 
28 #define USE_OFFSET_FOR_CONSTANT_FRAME true
29 
31 {
33  m_upperLinLimit = btScalar(-1.0);
60 
61  m_poweredLinMotor = false;
65 
66  m_poweredAngMotor = false;
70 
71  m_flags = 0;
72  m_flags = 0;
73 
75 
77 }
78 
79 
80 
81 
82 
83 btSliderConstraint::btSliderConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, bool useLinearReferenceFrameA)
86  m_frameInA(frameInA),
87  m_frameInB(frameInB),
88  m_useLinearReferenceFrameA(useLinearReferenceFrameA)
89 {
90  initParams();
91 }
92 
93 
94 
95 btSliderConstraint::btSliderConstraint(btRigidBody& rbB, const btTransform& frameInB, bool useLinearReferenceFrameA)
98  m_frameInB(frameInB),
99  m_useLinearReferenceFrameA(useLinearReferenceFrameA)
100 {
103 // m_frameInA.getOrigin() = m_rbA.getCenterOfMassTransform()(m_frameInA.getOrigin());
104 
105  initParams();
106 }
107 
108 
109 
110 
111 
112 
114 {
116  {
117  info->m_numConstraintRows = 0;
118  info->nub = 0;
119  }
120  else
121  {
122  info->m_numConstraintRows = 4; // Fixed 2 linear + 2 angular
123  info->nub = 2;
124  //prepare constraint
126  testAngLimits();
127  testLinLimits();
129  {
130  info->m_numConstraintRows++; // limit 3rd linear as well
131  info->nub--;
132  }
134  {
135  info->m_numConstraintRows++; // limit 3rd angular as well
136  info->nub--;
137  }
138  }
139 }
140 
142 {
143 
144  info->m_numConstraintRows = 6; // Fixed 2 linear + 2 angular + 1 limit (even if not used)
145  info->nub = 0;
146 }
147 
149 {
151 }
152 
153 
154 
155 
156 
157 
158 
160 {
162  {
165  }
166  else
167  {
170  }
175  {
177  }
178  else
179  {
181  }
183  btVector3 normalWorld;
184  int i;
185  //linear part
186  for(i = 0; i < 3; i++)
187  {
188  normalWorld = m_calculatedTransformA.getBasis().getColumn(i);
189  m_depth[i] = m_delta.dot(normalWorld);
190  }
191 }
192 
193 
194 
196 {
197  m_solveLinLim = false;
198  m_linPos = m_depth[0];
200  {
201  if(m_depth[0] > m_upperLinLimit)
202  {
203  m_depth[0] -= m_upperLinLimit;
204  m_solveLinLim = true;
205  }
206  else if(m_depth[0] < m_lowerLinLimit)
207  {
208  m_depth[0] -= m_lowerLinLimit;
209  m_solveLinLim = true;
210  }
211  else
212  {
213  m_depth[0] = btScalar(0.);
214  }
215  }
216  else
217  {
218  m_depth[0] = btScalar(0.);
219  }
220 }
221 
222 
223 
225 {
226  m_angDepth = btScalar(0.);
227  m_solveAngLim = false;
229  {
233 // btScalar rot = btAtan2Fast(axisB0.dot(axisA1), axisB0.dot(axisA0));
234  btScalar rot = btAtan2(axisB0.dot(axisA1), axisB0.dot(axisA0));
236  m_angPos = rot;
237  if(rot < m_lowerAngLimit)
238  {
239  m_angDepth = rot - m_lowerAngLimit;
240  m_solveAngLim = true;
241  }
242  else if(rot > m_upperAngLimit)
243  {
244  m_angDepth = rot - m_upperAngLimit;
245  m_solveAngLim = true;
246  }
247  }
248 }
249 
251 {
252  btVector3 ancorInA;
254  ancorInA = m_rbA.getCenterOfMassTransform().inverse() * ancorInA;
255  return ancorInA;
256 }
257 
258 
259 
261 {
262  btVector3 ancorInB;
263  ancorInB = m_frameInB.getOrigin();
264  return ancorInB;
265 }
266 
267 
268 void btSliderConstraint::getInfo2NonVirtual(btConstraintInfo2* info, const btTransform& transA,const btTransform& transB, const btVector3& linVelA,const btVector3& linVelB, btScalar rbAinvMass,btScalar rbBinvMass )
269 {
270  const btTransform& trA = getCalculatedTransformA();
271  const btTransform& trB = getCalculatedTransformB();
272 
274  int i, s = info->rowskip;
275 
276  btScalar signFact = m_useLinearReferenceFrameA ? btScalar(1.0f) : btScalar(-1.0f);
277 
278  // difference between frames in WCS
279  btVector3 ofs = trB.getOrigin() - trA.getOrigin();
280  // now get weight factors depending on masses
281  btScalar miA = rbAinvMass;
282  btScalar miB = rbBinvMass;
283  bool hasStaticBody = (miA < SIMD_EPSILON) || (miB < SIMD_EPSILON);
284  btScalar miS = miA + miB;
285  btScalar factA, factB;
286  if(miS > btScalar(0.f))
287  {
288  factA = miB / miS;
289  }
290  else
291  {
292  factA = btScalar(0.5f);
293  }
294  factB = btScalar(1.0f) - factA;
295  btVector3 ax1, p, q;
296  btVector3 ax1A = trA.getBasis().getColumn(0);
297  btVector3 ax1B = trB.getBasis().getColumn(0);
299  {
300  // get the desired direction of slider axis
301  // as weighted sum of X-orthos of frameA and frameB in WCS
302  ax1 = ax1A * factA + ax1B * factB;
303  ax1.normalize();
304  // construct two orthos to slider axis
305  btPlaneSpace1 (ax1, p, q);
306  }
307  else
308  { // old way - use frameA
309  ax1 = trA.getBasis().getColumn(0);
310  // get 2 orthos to slider axis (Y, Z)
311  p = trA.getBasis().getColumn(1);
312  q = trA.getBasis().getColumn(2);
313  }
314  // make rotations around these orthos equal
315  // the slider axis should be the only unconstrained
316  // rotational axis, the angular velocity of the two bodies perpendicular to
317  // the slider axis should be equal. thus the constraint equations are
318  // p*w1 - p*w2 = 0
319  // q*w1 - q*w2 = 0
320  // where p and q are unit vectors normal to the slider axis, and w1 and w2
321  // are the angular velocity vectors of the two bodies.
322  info->m_J1angularAxis[0] = p[0];
323  info->m_J1angularAxis[1] = p[1];
324  info->m_J1angularAxis[2] = p[2];
325  info->m_J1angularAxis[s+0] = q[0];
326  info->m_J1angularAxis[s+1] = q[1];
327  info->m_J1angularAxis[s+2] = q[2];
328 
329  info->m_J2angularAxis[0] = -p[0];
330  info->m_J2angularAxis[1] = -p[1];
331  info->m_J2angularAxis[2] = -p[2];
332  info->m_J2angularAxis[s+0] = -q[0];
333  info->m_J2angularAxis[s+1] = -q[1];
334  info->m_J2angularAxis[s+2] = -q[2];
335  // compute the right hand side of the constraint equation. set relative
336  // body velocities along p and q to bring the slider back into alignment.
337  // if ax1A,ax1B are the unit length slider axes as computed from bodyA and
338  // bodyB, we need to rotate both bodies along the axis u = (ax1 x ax2).
339  // if "theta" is the angle between ax1 and ax2, we need an angular velocity
340  // along u to cover angle erp*theta in one step :
341  // |angular_velocity| = angle/time = erp*theta / stepsize
342  // = (erp*fps) * theta
343  // angular_velocity = |angular_velocity| * (ax1 x ax2) / |ax1 x ax2|
344  // = (erp*fps) * theta * (ax1 x ax2) / sin(theta)
345  // ...as ax1 and ax2 are unit length. if theta is smallish,
346  // theta ~= sin(theta), so
347  // angular_velocity = (erp*fps) * (ax1 x ax2)
348  // ax1 x ax2 is in the plane space of ax1, so we project the angular
349  // velocity to p and q to find the right hand side.
350 // btScalar k = info->fps * info->erp * getSoftnessOrthoAng();
352  btScalar k = info->fps * currERP;
353 
354  btVector3 u = ax1A.cross(ax1B);
355  info->m_constraintError[0] = k * u.dot(p);
356  info->m_constraintError[s] = k * u.dot(q);
358  {
359  info->cfm[0] = m_cfmOrthoAng;
360  info->cfm[s] = m_cfmOrthoAng;
361  }
362 
363  int nrow = 1; // last filled row
364  int srow;
365  btScalar limit_err;
366  int limit;
367 
368  // next two rows.
369  // we want: velA + wA x relA == velB + wB x relB ... but this would
370  // result in three equations, so we project along two orthos to the slider axis
371 
372  btTransform bodyA_trans = transA;
373  btTransform bodyB_trans = transB;
374  nrow++;
375  int s2 = nrow * s;
376  nrow++;
377  int s3 = nrow * s;
378  btVector3 tmpA(0,0,0), tmpB(0,0,0), relA(0,0,0), relB(0,0,0), c(0,0,0);
380  {
381  // get vector from bodyB to frameB in WCS
382  relB = trB.getOrigin() - bodyB_trans.getOrigin();
383  // get its projection to slider axis
384  btVector3 projB = ax1 * relB.dot(ax1);
385  // get vector directed from bodyB to slider axis (and orthogonal to it)
386  btVector3 orthoB = relB - projB;
387  // same for bodyA
388  relA = trA.getOrigin() - bodyA_trans.getOrigin();
389  btVector3 projA = ax1 * relA.dot(ax1);
390  btVector3 orthoA = relA - projA;
391  // get desired offset between frames A and B along slider axis
392  btScalar sliderOffs = m_linPos - m_depth[0];
393  // desired vector from projection of center of bodyA to projection of center of bodyB to slider axis
394  btVector3 totalDist = projA + ax1 * sliderOffs - projB;
395  // get offset vectors relA and relB
396  relA = orthoA + totalDist * factA;
397  relB = orthoB - totalDist * factB;
398  // now choose average ortho to slider axis
399  p = orthoB * factA + orthoA * factB;
400  btScalar len2 = p.length2();
401  if(len2 > SIMD_EPSILON)
402  {
403  p /= btSqrt(len2);
404  }
405  else
406  {
407  p = trA.getBasis().getColumn(1);
408  }
409  // make one more ortho
410  q = ax1.cross(p);
411  // fill two rows
412  tmpA = relA.cross(p);
413  tmpB = relB.cross(p);
414  for (i=0; i<3; i++) info->m_J1angularAxis[s2+i] = tmpA[i];
415  for (i=0; i<3; i++) info->m_J2angularAxis[s2+i] = -tmpB[i];
416  tmpA = relA.cross(q);
417  tmpB = relB.cross(q);
418  if(hasStaticBody && getSolveAngLimit())
419  { // to make constraint between static and dynamic objects more rigid
420  // remove wA (or wB) from equation if angular limit is hit
421  tmpB *= factB;
422  tmpA *= factA;
423  }
424  for (i=0; i<3; i++) info->m_J1angularAxis[s3+i] = tmpA[i];
425  for (i=0; i<3; i++) info->m_J2angularAxis[s3+i] = -tmpB[i];
426  for (i=0; i<3; i++) info->m_J1linearAxis[s2+i] = p[i];
427  for (i=0; i<3; i++) info->m_J1linearAxis[s3+i] = q[i];
428  for (i=0; i<3; i++) info->m_J2linearAxis[s2+i] = -p[i];
429  for (i=0; i<3; i++) info->m_J2linearAxis[s3+i] = -q[i];
430  }
431  else
432  { // old way - maybe incorrect if bodies are not on the slider axis
433  // see discussion "Bug in slider constraint" http://bulletphysics.org/Bullet/phpBB3/viewtopic.php?f=9&t=4024&start=0
434  c = bodyB_trans.getOrigin() - bodyA_trans.getOrigin();
435  btVector3 tmp = c.cross(p);
436  for (i=0; i<3; i++) info->m_J1angularAxis[s2+i] = factA*tmp[i];
437  for (i=0; i<3; i++) info->m_J2angularAxis[s2+i] = factB*tmp[i];
438  tmp = c.cross(q);
439  for (i=0; i<3; i++) info->m_J1angularAxis[s3+i] = factA*tmp[i];
440  for (i=0; i<3; i++) info->m_J2angularAxis[s3+i] = factB*tmp[i];
441 
442  for (i=0; i<3; i++) info->m_J1linearAxis[s2+i] = p[i];
443  for (i=0; i<3; i++) info->m_J1linearAxis[s3+i] = q[i];
444  for (i=0; i<3; i++) info->m_J2linearAxis[s2+i] = -p[i];
445  for (i=0; i<3; i++) info->m_J2linearAxis[s3+i] = -q[i];
446  }
447  // compute two elements of right hand side
448 
449  // k = info->fps * info->erp * getSoftnessOrthoLin();
451  k = info->fps * currERP;
452 
453  btScalar rhs = k * p.dot(ofs);
454  info->m_constraintError[s2] = rhs;
455  rhs = k * q.dot(ofs);
456  info->m_constraintError[s3] = rhs;
458  {
459  info->cfm[s2] = m_cfmOrthoLin;
460  info->cfm[s3] = m_cfmOrthoLin;
461  }
462 
463 
464  // check linear limits
465  limit_err = btScalar(0.0);
466  limit = 0;
467  if(getSolveLinLimit())
468  {
469  limit_err = getLinDepth() * signFact;
470  limit = (limit_err > btScalar(0.0)) ? 2 : 1;
471  }
472  bool powered = getPoweredLinMotor();
473  // if the slider has joint limits or motor, add in the extra row
474  if (limit || powered)
475  {
476  nrow++;
477  srow = nrow * info->rowskip;
478  info->m_J1linearAxis[srow+0] = ax1[0];
479  info->m_J1linearAxis[srow+1] = ax1[1];
480  info->m_J1linearAxis[srow+2] = ax1[2];
481  info->m_J2linearAxis[srow+0] = -ax1[0];
482  info->m_J2linearAxis[srow+1] = -ax1[1];
483  info->m_J2linearAxis[srow+2] = -ax1[2];
484  // linear torque decoupling step:
485  //
486  // we have to be careful that the linear constraint forces (+/- ax1) applied to the two bodies
487  // do not create a torque couple. in other words, the points that the
488  // constraint force is applied at must lie along the same ax1 axis.
489  // a torque couple will result in limited slider-jointed free
490  // bodies from gaining angular momentum.
492  {
493  // this is needed only when bodyA and bodyB are both dynamic.
494  if(!hasStaticBody)
495  {
496  tmpA = relA.cross(ax1);
497  tmpB = relB.cross(ax1);
498  info->m_J1angularAxis[srow+0] = tmpA[0];
499  info->m_J1angularAxis[srow+1] = tmpA[1];
500  info->m_J1angularAxis[srow+2] = tmpA[2];
501  info->m_J2angularAxis[srow+0] = -tmpB[0];
502  info->m_J2angularAxis[srow+1] = -tmpB[1];
503  info->m_J2angularAxis[srow+2] = -tmpB[2];
504  }
505  }
506  else
507  { // The old way. May be incorrect if bodies are not on the slider axis
508  btVector3 ltd; // Linear Torque Decoupling vector (a torque)
509  ltd = c.cross(ax1);
510  info->m_J1angularAxis[srow+0] = factA*ltd[0];
511  info->m_J1angularAxis[srow+1] = factA*ltd[1];
512  info->m_J1angularAxis[srow+2] = factA*ltd[2];
513  info->m_J2angularAxis[srow+0] = factB*ltd[0];
514  info->m_J2angularAxis[srow+1] = factB*ltd[1];
515  info->m_J2angularAxis[srow+2] = factB*ltd[2];
516  }
517  // right-hand part
518  btScalar lostop = getLowerLinLimit();
519  btScalar histop = getUpperLinLimit();
520  if(limit && (lostop == histop))
521  { // the joint motor is ineffective
522  powered = false;
523  }
524  info->m_constraintError[srow] = 0.;
525  info->m_lowerLimit[srow] = 0.;
526  info->m_upperLimit[srow] = 0.;
527  currERP = (m_flags & BT_SLIDER_FLAGS_ERP_LIMLIN) ? m_softnessLimLin : info->erp;
528  if(powered)
529  {
531  {
532  info->cfm[srow] = m_cfmDirLin;
533  }
534  btScalar tag_vel = getTargetLinMotorVelocity();
535  btScalar mot_fact = getMotorFactor(m_linPos, m_lowerLinLimit, m_upperLinLimit, tag_vel, info->fps * currERP);
536  info->m_constraintError[srow] -= signFact * mot_fact * getTargetLinMotorVelocity();
537  info->m_lowerLimit[srow] += -getMaxLinMotorForce() / info->fps;
538  info->m_upperLimit[srow] += getMaxLinMotorForce() / info->fps;
539  }
540  if(limit)
541  {
542  k = info->fps * currERP;
543  info->m_constraintError[srow] += k * limit_err;
545  {
546  info->cfm[srow] = m_cfmLimLin;
547  }
548  if(lostop == histop)
549  { // limited low and high simultaneously
550  info->m_lowerLimit[srow] = -SIMD_INFINITY;
551  info->m_upperLimit[srow] = SIMD_INFINITY;
552  }
553  else if(limit == 1)
554  { // low limit
555  info->m_lowerLimit[srow] = -SIMD_INFINITY;
556  info->m_upperLimit[srow] = 0;
557  }
558  else
559  { // high limit
560  info->m_lowerLimit[srow] = 0;
561  info->m_upperLimit[srow] = SIMD_INFINITY;
562  }
563  // bounce (we'll use slider parameter abs(1.0 - m_dampingLimLin) for that)
564  btScalar bounce = btFabs(btScalar(1.0) - getDampingLimLin());
565  if(bounce > btScalar(0.0))
566  {
567  btScalar vel = linVelA.dot(ax1);
568  vel -= linVelB.dot(ax1);
569  vel *= signFact;
570  // only apply bounce if the velocity is incoming, and if the
571  // resulting c[] exceeds what we already have.
572  if(limit == 1)
573  { // low limit
574  if(vel < 0)
575  {
576  btScalar newc = -bounce * vel;
577  if (newc > info->m_constraintError[srow])
578  {
579  info->m_constraintError[srow] = newc;
580  }
581  }
582  }
583  else
584  { // high limit - all those computations are reversed
585  if(vel > 0)
586  {
587  btScalar newc = -bounce * vel;
588  if(newc < info->m_constraintError[srow])
589  {
590  info->m_constraintError[srow] = newc;
591  }
592  }
593  }
594  }
595  info->m_constraintError[srow] *= getSoftnessLimLin();
596  } // if(limit)
597  } // if linear limit
598  // check angular limits
599  limit_err = btScalar(0.0);
600  limit = 0;
601  if(getSolveAngLimit())
602  {
603  limit_err = getAngDepth();
604  limit = (limit_err > btScalar(0.0)) ? 1 : 2;
605  }
606  // if the slider has joint limits, add in the extra row
607  powered = getPoweredAngMotor();
608  if(limit || powered)
609  {
610  nrow++;
611  srow = nrow * info->rowskip;
612  info->m_J1angularAxis[srow+0] = ax1[0];
613  info->m_J1angularAxis[srow+1] = ax1[1];
614  info->m_J1angularAxis[srow+2] = ax1[2];
615 
616  info->m_J2angularAxis[srow+0] = -ax1[0];
617  info->m_J2angularAxis[srow+1] = -ax1[1];
618  info->m_J2angularAxis[srow+2] = -ax1[2];
619 
620  btScalar lostop = getLowerAngLimit();
621  btScalar histop = getUpperAngLimit();
622  if(limit && (lostop == histop))
623  { // the joint motor is ineffective
624  powered = false;
625  }
626  currERP = (m_flags & BT_SLIDER_FLAGS_ERP_LIMANG) ? m_softnessLimAng : info->erp;
627  if(powered)
628  {
630  {
631  info->cfm[srow] = m_cfmDirAng;
632  }
633  btScalar mot_fact = getMotorFactor(m_angPos, m_lowerAngLimit, m_upperAngLimit, getTargetAngMotorVelocity(), info->fps * currERP);
634  info->m_constraintError[srow] = mot_fact * getTargetAngMotorVelocity();
635  info->m_lowerLimit[srow] = -getMaxAngMotorForce() / info->fps;
636  info->m_upperLimit[srow] = getMaxAngMotorForce() / info->fps;
637  }
638  if(limit)
639  {
640  k = info->fps * currERP;
641  info->m_constraintError[srow] += k * limit_err;
643  {
644  info->cfm[srow] = m_cfmLimAng;
645  }
646  if(lostop == histop)
647  {
648  // limited low and high simultaneously
649  info->m_lowerLimit[srow] = -SIMD_INFINITY;
650  info->m_upperLimit[srow] = SIMD_INFINITY;
651  }
652  else if(limit == 1)
653  { // low limit
654  info->m_lowerLimit[srow] = 0;
655  info->m_upperLimit[srow] = SIMD_INFINITY;
656  }
657  else
658  { // high limit
659  info->m_lowerLimit[srow] = -SIMD_INFINITY;
660  info->m_upperLimit[srow] = 0;
661  }
662  // bounce (we'll use slider parameter abs(1.0 - m_dampingLimAng) for that)
663  btScalar bounce = btFabs(btScalar(1.0) - getDampingLimAng());
664  if(bounce > btScalar(0.0))
665  {
666  btScalar vel = m_rbA.getAngularVelocity().dot(ax1);
667  vel -= m_rbB.getAngularVelocity().dot(ax1);
668  // only apply bounce if the velocity is incoming, and if the
669  // resulting c[] exceeds what we already have.
670  if(limit == 1)
671  { // low limit
672  if(vel < 0)
673  {
674  btScalar newc = -bounce * vel;
675  if(newc > info->m_constraintError[srow])
676  {
677  info->m_constraintError[srow] = newc;
678  }
679  }
680  }
681  else
682  { // high limit - all those computations are reversed
683  if(vel > 0)
684  {
685  btScalar newc = -bounce * vel;
686  if(newc < info->m_constraintError[srow])
687  {
688  info->m_constraintError[srow] = newc;
689  }
690  }
691  }
692  }
693  info->m_constraintError[srow] *= getSoftnessLimAng();
694  } // if(limit)
695  } // if angular limit or powered
696 }
697 
698 
701 void btSliderConstraint::setParam(int num, btScalar value, int axis)
702 {
703  switch(num)
704  {
706  if(axis < 1)
707  {
708  m_softnessLimLin = value;
710  }
711  else if(axis < 3)
712  {
713  m_softnessOrthoLin = value;
715  }
716  else if(axis == 3)
717  {
718  m_softnessLimAng = value;
720  }
721  else if(axis < 6)
722  {
723  m_softnessOrthoAng = value;
725  }
726  else
727  {
729  }
730  break;
731  case BT_CONSTRAINT_CFM :
732  if(axis < 1)
733  {
734  m_cfmDirLin = value;
736  }
737  else if(axis == 3)
738  {
739  m_cfmDirAng = value;
741  }
742  else
743  {
745  }
746  break;
748  if(axis < 1)
749  {
750  m_cfmLimLin = value;
752  }
753  else if(axis < 3)
754  {
755  m_cfmOrthoLin = value;
757  }
758  else if(axis == 3)
759  {
760  m_cfmLimAng = value;
762  }
763  else if(axis < 6)
764  {
765  m_cfmOrthoAng = value;
767  }
768  else
769  {
771  }
772  break;
773  }
774 }
775 
777 btScalar btSliderConstraint::getParam(int num, int axis) const
778 {
779  btScalar retVal(SIMD_INFINITY);
780  switch(num)
781  {
783  if(axis < 1)
784  {
786  retVal = m_softnessLimLin;
787  }
788  else if(axis < 3)
789  {
791  retVal = m_softnessOrthoLin;
792  }
793  else if(axis == 3)
794  {
796  retVal = m_softnessLimAng;
797  }
798  else if(axis < 6)
799  {
801  retVal = m_softnessOrthoAng;
802  }
803  else
804  {
806  }
807  break;
808  case BT_CONSTRAINT_CFM :
809  if(axis < 1)
810  {
812  retVal = m_cfmDirLin;
813  }
814  else if(axis == 3)
815  {
817  retVal = m_cfmDirAng;
818  }
819  else
820  {
822  }
823  break;
825  if(axis < 1)
826  {
828  retVal = m_cfmLimLin;
829  }
830  else if(axis < 3)
831  {
833  retVal = m_cfmOrthoLin;
834  }
835  else if(axis == 3)
836  {
838  retVal = m_cfmLimAng;
839  }
840  else if(axis < 6)
841  {
843  retVal = m_cfmOrthoAng;
844  }
845  else
846  {
848  }
849  break;
850  }
851  return retVal;
852 }
853 
854 
855 
btScalar getInvMass() const
Definition: btRigidBody.h:273
void calculateTransforms(const btTransform &transA, const btTransform &transB)
#define SLIDER_CONSTRAINT_DEF_RESTITUTION
#define SIMD_EPSILON
Definition: btScalar.h:521
btScalar getMaxAngMotorForce()
const btTransform & getCalculatedTransformA() const
const btTransform & getCalculatedTransformB() const
#define USE_OFFSET_FOR_CONSTANT_FRAME
void getInfo2NonVirtual(btConstraintInfo2 *info, const btTransform &transA, const btTransform &transB, const btVector3 &linVelA, const btVector3 &linVelB, btScalar rbAinvMass, btScalar rbBinvMass)
virtual void getInfo2(btConstraintInfo2 *info)
internal method used by the constraint solver, don&#39;t use them directly
btScalar m_accumulatedAngMotorImpulse
void btPlaneSpace1(const T &n, T &p, T &q)
Definition: btVector3.h:1284
btScalar btSqrt(btScalar y)
Definition: btScalar.h:444
#define btAssert(x)
Definition: btScalar.h:131
btScalar m_accumulatedLinMotorImpulse
btTransform m_calculatedTransformB
btVector3 getColumn(int i) const
Get a column of the matrix as a vector.
Definition: btMatrix3x3.h:134
btScalar dot(const btVector3 &v) const
Return the dot product.
Definition: btVector3.h:235
btVector3 & normalize()
Normalize this vector x^2 + y^2 + z^2 = 1.
Definition: btVector3.h:309
btSliderConstraint(btRigidBody &rbA, btRigidBody &rbB, const btTransform &frameInA, const btTransform &frameInB, bool useLinearReferenceFrameA)
btScalar getMaxLinMotorForce()
#define SIMD_INFINITY
Definition: btScalar.h:522
btVector3 & getOrigin()
Return the origin vector translation.
Definition: btTransform.h:117
const btTransform & getCenterOfMassTransform() const
Definition: btRigidBody.h:359
btScalar btAtan2(btScalar x, btScalar y)
Definition: btScalar.h:496
#define SLIDER_CONSTRAINT_DEF_CFM
const btVector3 & getAngularVelocity() const
Definition: btRigidBody.h:365
btVector3 cross(const btVector3 &v) const
Return the cross product between this and another vector.
Definition: btVector3.h:389
btMatrix3x3 & getBasis()
Return the basis matrix for the rotation.
Definition: btTransform.h:112
The btRigidBody is the main class for rigid body objects.
Definition: btRigidBody.h:62
virtual btScalar getParam(int num, int axis=-1) const
return the local value of parameter
btTransform inverse() const
Return the inverse of this transform.
Definition: btTransform.h:188
virtual void getInfo1(btConstraintInfo1 *info)
internal method used by the constraint solver, don&#39;t use them directly
btScalar getTargetLinMotorVelocity()
#define SLIDER_CONSTRAINT_DEF_SOFTNESS
void getInfo1NonVirtual(btConstraintInfo1 *info)
btScalar btAdjustAngleToLimits(btScalar angleInRadians, btScalar angleLowerLimitInRadians, btScalar angleUpperLimitInRadians)
btVector3 can be used to represent 3D points and vectors.
Definition: btVector3.h:83
btScalar length2() const
Return the length of the vector squared.
Definition: btVector3.h:257
static btRigidBody & getFixedBody()
The btTransform class supports rigid transforms with only translation and rotation and no scaling/she...
Definition: btTransform.h:34
btScalar getTargetAngMotorVelocity()
btTransform m_calculatedTransformA
TypedConstraint is the baseclass for Bullet constraints and vehicles.
btScalar getMotorFactor(btScalar pos, btScalar lowLim, btScalar uppLim, btScalar vel, btScalar timeFact)
internal method used by the constraint solver, don&#39;t use them directly
bool m_useSolveConstraintObsolete
for backwards compatibility during the transition to &#39;getInfo/getInfo2&#39;
const btVector3 & getLinearVelocity() const
Definition: btRigidBody.h:362
#define btAssertConstrParams(_par)
#define SLIDER_CONSTRAINT_DEF_DAMPING
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: btScalar.h:292
virtual void setParam(int num, btScalar value, int axis=-1)
override the default global value of a parameter (such as ERP or CFM), optionally provide the axis (0...
btScalar btFabs(btScalar x)
Definition: btScalar.h:475