Bullet Collision Detection & Physics Library
btGeneric6DofSpring2Constraint.h
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 2014 May: btGeneric6DofSpring2Constraint is created from the original (2.82.2712) btGeneric6DofConstraint by Gabor Puhr and Tamas Umenhoffer
18 Pros:
19 - Much more accurate and stable in a lot of situation. (Especially when a sleeping chain of RBs connected with 6dof2 is pulled)
20 - Stable and accurate spring with minimal energy loss that works with all of the solvers. (latter is not true for the original 6dof spring)
21 - Servo motor functionality
22 - Much more accurate bouncing. 0 really means zero bouncing (not true for the original 6odf) and there is only a minimal energy loss when the value is 1 (because of the solvers' precision)
23 - Rotation order for the Euler system can be set. (One axis' freedom is still limited to pi/2)
24 
25 Cons:
26 - It is slower than the original 6dof. There is no exact ratio, but half speed is a good estimation.
27 - At bouncing the correct velocity is calculated, but not the correct position. (it is because of the solver can correct position or velocity, but not both.)
28 */
29 
32 
33 /*
34 2007-09-09
35 btGeneric6DofConstraint Refactored by Francisco Le?n
36 email: projectileman@yahoo.com
37 http://gimpact.sf.net
38 */
39 
40 
41 #ifndef BT_GENERIC_6DOF_CONSTRAINT2_H
42 #define BT_GENERIC_6DOF_CONSTRAINT2_H
43 
44 #include "LinearMath/btVector3.h"
45 #include "btJacobianEntry.h"
46 #include "btTypedConstraint.h"
47 
48 class btRigidBody;
49 
50 
51 #ifdef BT_USE_DOUBLE_PRECISION
52 #define btGeneric6DofSpring2ConstraintData2 btGeneric6DofSpring2ConstraintDoubleData2
53 #define btGeneric6DofSpring2ConstraintDataName "btGeneric6DofSpring2ConstraintDoubleData2"
54 #else
55 #define btGeneric6DofSpring2ConstraintData2 btGeneric6DofSpring2ConstraintData
56 #define btGeneric6DofSpring2ConstraintDataName "btGeneric6DofSpring2ConstraintData"
57 #endif //BT_USE_DOUBLE_PRECISION
58 
60 {
61  RO_XYZ=0,
67 };
68 
70 {
71 public:
72 // upper < lower means free
73 // upper == lower means locked
74 // upper > lower means limited
93 
98 
100  {
101  m_loLimit = 1.0f;
102  m_hiLimit = -1.0f;
103  m_bounce = 0.0f;
104  m_stopERP = 0.2f;
105  m_stopCFM = 0.f;
106  m_motorERP = 0.9f;
107  m_motorCFM = 0.f;
108  m_enableMotor = false;
109  m_targetVelocity = 0;
110  m_maxMotorForce = 6.0f;
111  m_servoMotor = false;
112  m_servoTarget = 0;
113  m_enableSpring = false;
114  m_springStiffness = 0;
115  m_springStiffnessLimited = false;
116  m_springDamping = 0;
117  m_springDampingLimited = false;
118  m_equilibriumPoint = 0;
119 
120  m_currentLimitError = 0;
121  m_currentLimitErrorHi = 0;
122  m_currentPosition = 0;
123  m_currentLimit = 0;
124  }
125 
127  {
128  m_loLimit = limot.m_loLimit;
129  m_hiLimit = limot.m_hiLimit;
130  m_bounce = limot.m_bounce;
131  m_stopERP = limot.m_stopERP;
132  m_stopCFM = limot.m_stopCFM;
133  m_motorERP = limot.m_motorERP;
134  m_motorCFM = limot.m_motorCFM;
135  m_enableMotor = limot.m_enableMotor;
136  m_targetVelocity = limot.m_targetVelocity;
137  m_maxMotorForce = limot.m_maxMotorForce;
138  m_servoMotor = limot.m_servoMotor;
139  m_servoTarget = limot.m_servoTarget;
140  m_enableSpring = limot.m_enableSpring;
141  m_springStiffness = limot.m_springStiffness;
142  m_springStiffnessLimited = limot.m_springStiffnessLimited;
143  m_springDamping = limot.m_springDamping;
144  m_springDampingLimited = limot.m_springDampingLimited;
145  m_equilibriumPoint = limot.m_equilibriumPoint;
146 
147  m_currentLimitError = limot.m_currentLimitError;
148  m_currentLimitErrorHi = limot.m_currentLimitErrorHi;
149  m_currentPosition = limot.m_currentPosition;
150  m_currentLimit = limot.m_currentLimit;
151  }
152 
153 
154  bool isLimited()
155  {
156  if(m_loLimit > m_hiLimit) return false;
157  return true;
158  }
159 
160  void testLimitValue(btScalar test_value);
161 };
162 
163 
164 
166 {
167 public:
168 // upper < lower means free
169 // upper == lower means locked
170 // upper > lower means limited
178  bool m_enableMotor[3];
179  bool m_servoMotor[3];
180  bool m_enableSpring[3];
189 
194 
196  {
197  m_lowerLimit .setValue(0.f , 0.f , 0.f );
198  m_upperLimit .setValue(0.f , 0.f , 0.f );
199  m_bounce .setValue(0.f , 0.f , 0.f );
200  m_stopERP .setValue(0.2f, 0.2f, 0.2f);
201  m_stopCFM .setValue(0.f , 0.f , 0.f );
202  m_motorERP .setValue(0.9f, 0.9f, 0.9f);
203  m_motorCFM .setValue(0.f , 0.f , 0.f );
204 
205  m_currentLimitError .setValue(0.f , 0.f , 0.f );
206  m_currentLimitErrorHi.setValue(0.f , 0.f , 0.f );
207  m_currentLinearDiff .setValue(0.f , 0.f , 0.f );
208 
209  for(int i=0; i < 3; i++)
210  {
211  m_enableMotor[i] = false;
212  m_servoMotor[i] = false;
213  m_enableSpring[i] = false;
214  m_servoTarget[i] = btScalar(0.f);
215  m_springStiffness[i] = btScalar(0.f);
216  m_springStiffnessLimited[i] = false;
217  m_springDamping[i] = btScalar(0.f);
218  m_springDampingLimited[i] = false;
219  m_equilibriumPoint[i] = btScalar(0.f);
220  m_targetVelocity[i] = btScalar(0.f);
221  m_maxMotorForce[i] = btScalar(0.f);
222 
223  m_currentLimit[i] = 0;
224  }
225  }
226 
228  {
229  m_lowerLimit = other.m_lowerLimit;
230  m_upperLimit = other.m_upperLimit;
231  m_bounce = other.m_bounce;
232  m_stopERP = other.m_stopERP;
233  m_stopCFM = other.m_stopCFM;
234  m_motorERP = other.m_motorERP;
235  m_motorCFM = other.m_motorCFM;
236 
237  m_currentLimitError = other.m_currentLimitError;
238  m_currentLimitErrorHi = other.m_currentLimitErrorHi;
239  m_currentLinearDiff = other.m_currentLinearDiff;
240 
241  for(int i=0; i < 3; i++)
242  {
243  m_enableMotor[i] = other.m_enableMotor[i];
244  m_servoMotor[i] = other.m_servoMotor[i];
245  m_enableSpring[i] = other.m_enableSpring[i];
246  m_servoTarget[i] = other.m_servoTarget[i];
247  m_springStiffness[i] = other.m_springStiffness[i];
248  m_springStiffnessLimited[i] = other.m_springStiffnessLimited[i];
249  m_springDamping[i] = other.m_springDamping[i];
250  m_springDampingLimited[i] = other.m_springDampingLimited[i];
251  m_equilibriumPoint[i] = other.m_equilibriumPoint[i];
252  m_targetVelocity[i] = other.m_targetVelocity[i];
253  m_maxMotorForce[i] = other.m_maxMotorForce[i];
254 
255  m_currentLimit[i] = other.m_currentLimit[i];
256  }
257  }
258 
259  inline bool isLimited(int limitIndex)
260  {
261  return (m_upperLimit[limitIndex] >= m_lowerLimit[limitIndex]);
262  }
263 
264  void testLimitValue(int limitIndex, btScalar test_value);
265 };
266 
268 {
273 };
274 #define BT_6DOF_FLAGS_AXIS_SHIFT2 4 // bits per axis
275 
276 
278 {
279 protected:
280 
283 
284  btJacobianEntry m_jacLinear[3];
285  btJacobianEntry m_jacAng[3];
286 
288  btRotationalLimitMotor2 m_angularLimits[3];
289 
291 
292 protected:
293 
297  btVector3 m_calculatedAxis[3];
302  int m_flags;
303 
305  {
306  btAssert(0);
307  return *this;
308  }
309 
310  int setAngularLimits(btConstraintInfo2 *info, int row_offset,const btTransform& transA,const btTransform& transB,const btVector3& linVelA,const btVector3& linVelB,const btVector3& angVelA,const btVector3& angVelB);
311  int setLinearLimits(btConstraintInfo2 *info, int row, const btTransform& transA,const btTransform& transB,const btVector3& linVelA,const btVector3& linVelB,const btVector3& angVelA,const btVector3& angVelB);
312 
313  void calculateLinearInfo();
314  void calculateAngleInfo();
315  void testAngularLimitMotor(int axis_index);
316 
317  void calculateJacobi(btRotationalLimitMotor2* limot, const btTransform& transA,const btTransform& transB, btConstraintInfo2* info, int srow, btVector3& ax1, int rotational, int rotAllowed);
318  int get_limit_motor_info2(btRotationalLimitMotor2* limot,
319  const btTransform& transA,const btTransform& transB,const btVector3& linVelA,const btVector3& linVelB,const btVector3& angVelA,const btVector3& angVelB,
320  btConstraintInfo2* info, int row, btVector3& ax1, int rotational, int rotAllowed = false);
321 
322 public:
323 
325 
326  btGeneric6DofSpring2Constraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, RotateOrder rotOrder = RO_XYZ);
327  btGeneric6DofSpring2Constraint(btRigidBody& rbB, const btTransform& frameInB, RotateOrder rotOrder = RO_XYZ);
328 
329  virtual void buildJacobian() {}
330  virtual void getInfo1 (btConstraintInfo1* info);
331  virtual void getInfo2 (btConstraintInfo2* info);
332  virtual int calculateSerializeBufferSize() const;
333  virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const;
334 
335  btRotationalLimitMotor2* getRotationalLimitMotor(int index) { return &m_angularLimits[index]; }
337 
338  // Calculates the global transform for the joint offset for body A an B, and also calculates the angle differences between the bodies.
339  void calculateTransforms(const btTransform& transA,const btTransform& transB);
340  void calculateTransforms();
341 
342  // Gets the global transform of the offset for body A
343  const btTransform & getCalculatedTransformA() const { return m_calculatedTransformA; }
344  // Gets the global transform of the offset for body B
345  const btTransform & getCalculatedTransformB() const { return m_calculatedTransformB; }
346 
347  const btTransform & getFrameOffsetA() const { return m_frameInA; }
348  const btTransform & getFrameOffsetB() const { return m_frameInB; }
349 
350  btTransform & getFrameOffsetA() { return m_frameInA; }
351  btTransform & getFrameOffsetB() { return m_frameInB; }
352 
353  // Get the rotation axis in global coordinates ( btGeneric6DofSpring2Constraint::calculateTransforms() must be called previously )
354  btVector3 getAxis(int axis_index) const { return m_calculatedAxis[axis_index]; }
355 
356  // Get the relative Euler angle ( btGeneric6DofSpring2Constraint::calculateTransforms() must be called previously )
357  btScalar getAngle(int axis_index) const { return m_calculatedAxisAngleDiff[axis_index]; }
358 
359  // Get the relative position of the constraint pivot ( btGeneric6DofSpring2Constraint::calculateTransforms() must be called previously )
360  btScalar getRelativePivotPosition(int axis_index) const { return m_calculatedLinearDiff[axis_index]; }
361 
362  void setFrames(const btTransform & frameA, const btTransform & frameB);
363 
364  void setLinearLowerLimit(const btVector3& linearLower) { m_linearLimits.m_lowerLimit = linearLower; }
365  void getLinearLowerLimit(btVector3& linearLower) { linearLower = m_linearLimits.m_lowerLimit; }
366  void setLinearUpperLimit(const btVector3& linearUpper) { m_linearLimits.m_upperLimit = linearUpper; }
367  void getLinearUpperLimit(btVector3& linearUpper) { linearUpper = m_linearLimits.m_upperLimit; }
368 
369  void setAngularLowerLimit(const btVector3& angularLower)
370  {
371  for(int i = 0; i < 3; i++)
372  m_angularLimits[i].m_loLimit = btNormalizeAngle(angularLower[i]);
373  }
374 
375  void setAngularLowerLimitReversed(const btVector3& angularLower)
376  {
377  for(int i = 0; i < 3; i++)
378  m_angularLimits[i].m_hiLimit = btNormalizeAngle(-angularLower[i]);
379  }
380 
381  void getAngularLowerLimit(btVector3& angularLower)
382  {
383  for(int i = 0; i < 3; i++)
384  angularLower[i] = m_angularLimits[i].m_loLimit;
385  }
386 
388  {
389  for(int i = 0; i < 3; i++)
390  angularLower[i] = -m_angularLimits[i].m_hiLimit;
391  }
392 
393  void setAngularUpperLimit(const btVector3& angularUpper)
394  {
395  for(int i = 0; i < 3; i++)
396  m_angularLimits[i].m_hiLimit = btNormalizeAngle(angularUpper[i]);
397  }
398 
399  void setAngularUpperLimitReversed(const btVector3& angularUpper)
400  {
401  for(int i = 0; i < 3; i++)
402  m_angularLimits[i].m_loLimit = btNormalizeAngle(-angularUpper[i]);
403  }
404 
405  void getAngularUpperLimit(btVector3& angularUpper)
406  {
407  for(int i = 0; i < 3; i++)
408  angularUpper[i] = m_angularLimits[i].m_hiLimit;
409  }
410 
412  {
413  for(int i = 0; i < 3; i++)
414  angularUpper[i] = -m_angularLimits[i].m_loLimit;
415  }
416 
417  //first 3 are linear, next 3 are angular
418 
419  void setLimit(int axis, btScalar lo, btScalar hi)
420  {
421  if(axis<3)
422  {
423  m_linearLimits.m_lowerLimit[axis] = lo;
424  m_linearLimits.m_upperLimit[axis] = hi;
425  }
426  else
427  {
428  lo = btNormalizeAngle(lo);
429  hi = btNormalizeAngle(hi);
430  m_angularLimits[axis-3].m_loLimit = lo;
431  m_angularLimits[axis-3].m_hiLimit = hi;
432  }
433  }
434 
435  void setLimitReversed(int axis, btScalar lo, btScalar hi)
436  {
437  if(axis<3)
438  {
439  m_linearLimits.m_lowerLimit[axis] = lo;
440  m_linearLimits.m_upperLimit[axis] = hi;
441  }
442  else
443  {
444  lo = btNormalizeAngle(lo);
445  hi = btNormalizeAngle(hi);
446  m_angularLimits[axis-3].m_hiLimit = -lo;
447  m_angularLimits[axis-3].m_loLimit = -hi;
448  }
449  }
450 
451  bool isLimited(int limitIndex)
452  {
453  if(limitIndex<3)
454  {
455  return m_linearLimits.isLimited(limitIndex);
456  }
457  return m_angularLimits[limitIndex-3].isLimited();
458  }
459 
460  void setRotationOrder(RotateOrder order) { m_rotateOrder = order; }
461  RotateOrder getRotationOrder() { return m_rotateOrder; }
462 
463  void setAxis( const btVector3& axis1, const btVector3& axis2);
464 
465  void setBounce(int index, btScalar bounce);
466 
467  void enableMotor(int index, bool onOff);
468  void setServo(int index, bool onOff); // set the type of the motor (servo or not) (the motor has to be turned on for servo also)
469  void setTargetVelocity(int index, btScalar velocity);
470  void setServoTarget(int index, btScalar target);
471  void setMaxMotorForce(int index, btScalar force);
472 
473  void enableSpring(int index, bool onOff);
474  void setStiffness(int index, btScalar stiffness, bool limitIfNeeded = true); // if limitIfNeeded is true the system will automatically limit the stiffness in necessary situations where otherwise the spring would move unrealistically too widely
475  void setDamping(int index, btScalar damping, bool limitIfNeeded = true); // if limitIfNeeded is true the system will automatically limit the damping in necessary situations where otherwise the spring would blow up
476  void setEquilibriumPoint(); // set the current constraint position/orientation as an equilibrium point for all DOF
477  void setEquilibriumPoint(int index); // set the current constraint position/orientation as an equilibrium point for given DOF
478  void setEquilibriumPoint(int index, btScalar val);
479 
480  //override the default global value of a parameter (such as ERP or CFM), optionally provide the axis (0..5).
481  //If no axis is provided, it uses the default axis for this constraint.
482  virtual void setParam(int num, btScalar value, int axis = -1);
483  virtual btScalar getParam(int num, int axis = -1) const;
484 
485  static btScalar btGetMatrixElem(const btMatrix3x3& mat, int index);
486  static bool matrixToEulerXYZ(const btMatrix3x3& mat,btVector3& xyz);
487  static bool matrixToEulerXZY(const btMatrix3x3& mat,btVector3& xyz);
488  static bool matrixToEulerYXZ(const btMatrix3x3& mat,btVector3& xyz);
489  static bool matrixToEulerYZX(const btMatrix3x3& mat,btVector3& xyz);
490  static bool matrixToEulerZXY(const btMatrix3x3& mat,btVector3& xyz);
491  static bool matrixToEulerZYX(const btMatrix3x3& mat,btVector3& xyz);
492 };
493 
494 
496 {
500 
514  char m_linearEnableMotor[4];
515  char m_linearServoMotor[4];
516  char m_linearEnableSpring[4];
517  char m_linearSpringStiffnessLimited[4];
518  char m_linearSpringDampingLimited[4];
519  char m_padding1[4];
520 
534  char m_angularEnableMotor[4];
535  char m_angularServoMotor[4];
536  char m_angularEnableSpring[4];
537  char m_angularSpringStiffnessLimited[4];
538  char m_angularSpringDampingLimited[4];
539 
541 };
542 
544 {
548 
562  char m_linearEnableMotor[4];
563  char m_linearServoMotor[4];
564  char m_linearEnableSpring[4];
565  char m_linearSpringStiffnessLimited[4];
566  char m_linearSpringDampingLimited[4];
567  char m_padding1[4];
568 
582  char m_angularEnableMotor[4];
583  char m_angularServoMotor[4];
584  char m_angularEnableSpring[4];
585  char m_angularSpringStiffnessLimited[4];
586  char m_angularSpringDampingLimited[4];
587 
589 };
590 
592 {
594 }
595 
596 SIMD_FORCE_INLINE const char* btGeneric6DofSpring2Constraint::serialize(void* dataBuffer, btSerializer* serializer) const
597 {
599  btTypedConstraint::serialize(&dof->m_typeConstraintData,serializer);
600 
601  m_frameInA.serialize(dof->m_rbAFrame);
602  m_frameInB.serialize(dof->m_rbBFrame);
603 
604  int i;
605  for (i=0;i<3;i++)
606  {
607  dof->m_angularLowerLimit.m_floats[i] = m_angularLimits[i].m_loLimit;
608  dof->m_angularUpperLimit.m_floats[i] = m_angularLimits[i].m_hiLimit;
609  dof->m_angularBounce.m_floats[i] = m_angularLimits[i].m_bounce;
610  dof->m_angularStopERP.m_floats[i] = m_angularLimits[i].m_stopERP;
611  dof->m_angularStopCFM.m_floats[i] = m_angularLimits[i].m_stopCFM;
612  dof->m_angularMotorERP.m_floats[i] = m_angularLimits[i].m_motorERP;
613  dof->m_angularMotorCFM.m_floats[i] = m_angularLimits[i].m_motorCFM;
614  dof->m_angularTargetVelocity.m_floats[i] = m_angularLimits[i].m_targetVelocity;
615  dof->m_angularMaxMotorForce.m_floats[i] = m_angularLimits[i].m_maxMotorForce;
616  dof->m_angularServoTarget.m_floats[i] = m_angularLimits[i].m_servoTarget;
617  dof->m_angularSpringStiffness.m_floats[i] = m_angularLimits[i].m_springStiffness;
618  dof->m_angularSpringDamping.m_floats[i] = m_angularLimits[i].m_springDamping;
619  dof->m_angularEquilibriumPoint.m_floats[i] = m_angularLimits[i].m_equilibriumPoint;
620  }
621  dof->m_angularLowerLimit.m_floats[3] = 0;
622  dof->m_angularUpperLimit.m_floats[3] = 0;
623  dof->m_angularBounce.m_floats[3] = 0;
624  dof->m_angularStopERP.m_floats[3] = 0;
625  dof->m_angularStopCFM.m_floats[3] = 0;
626  dof->m_angularMotorERP.m_floats[3] = 0;
627  dof->m_angularMotorCFM.m_floats[3] = 0;
628  dof->m_angularTargetVelocity.m_floats[3] = 0;
629  dof->m_angularMaxMotorForce.m_floats[3] = 0;
630  dof->m_angularServoTarget.m_floats[3] = 0;
631  dof->m_angularSpringStiffness.m_floats[3] = 0;
632  dof->m_angularSpringDamping.m_floats[3] = 0;
633  dof->m_angularEquilibriumPoint.m_floats[3] = 0;
634  for (i=0;i<4;i++)
635  {
636  dof->m_angularEnableMotor[i] = i < 3 ? ( m_angularLimits[i].m_enableMotor ? 1 : 0 ) : 0;
637  dof->m_angularServoMotor[i] = i < 3 ? ( m_angularLimits[i].m_servoMotor ? 1 : 0 ) : 0;
638  dof->m_angularEnableSpring[i] = i < 3 ? ( m_angularLimits[i].m_enableSpring ? 1 : 0 ) : 0;
639  dof->m_angularSpringStiffnessLimited[i] = i < 3 ? ( m_angularLimits[i].m_springStiffnessLimited ? 1 : 0 ) : 0;
640  dof->m_angularSpringDampingLimited[i] = i < 3 ? ( m_angularLimits[i].m_springDampingLimited ? 1 : 0 ) : 0;
641  }
642 
643  m_linearLimits.m_lowerLimit.serialize( dof->m_linearLowerLimit );
644  m_linearLimits.m_upperLimit.serialize( dof->m_linearUpperLimit );
645  m_linearLimits.m_bounce.serialize( dof->m_linearBounce );
646  m_linearLimits.m_stopERP.serialize( dof->m_linearStopERP );
647  m_linearLimits.m_stopCFM.serialize( dof->m_linearStopCFM );
648  m_linearLimits.m_motorERP.serialize( dof->m_linearMotorERP );
649  m_linearLimits.m_motorCFM.serialize( dof->m_linearMotorCFM );
650  m_linearLimits.m_targetVelocity.serialize( dof->m_linearTargetVelocity );
651  m_linearLimits.m_maxMotorForce.serialize( dof->m_linearMaxMotorForce );
652  m_linearLimits.m_servoTarget.serialize( dof->m_linearServoTarget );
653  m_linearLimits.m_springStiffness.serialize( dof->m_linearSpringStiffness );
654  m_linearLimits.m_springDamping.serialize( dof->m_linearSpringDamping );
655  m_linearLimits.m_equilibriumPoint.serialize( dof->m_linearEquilibriumPoint );
656  for (i=0;i<4;i++)
657  {
658  dof->m_linearEnableMotor[i] = i < 3 ? ( m_linearLimits.m_enableMotor[i] ? 1 : 0 ) : 0;
659  dof->m_linearServoMotor[i] = i < 3 ? ( m_linearLimits.m_servoMotor[i] ? 1 : 0 ) : 0;
660  dof->m_linearEnableSpring[i] = i < 3 ? ( m_linearLimits.m_enableSpring[i] ? 1 : 0 ) : 0;
661  dof->m_linearSpringStiffnessLimited[i] = i < 3 ? ( m_linearLimits.m_springStiffnessLimited[i] ? 1 : 0 ) : 0;
662  dof->m_linearSpringDampingLimited[i] = i < 3 ? ( m_linearLimits.m_springDampingLimited[i] ? 1 : 0 ) : 0;
663  }
664 
665  dof->m_rotateOrder = m_rotateOrder;
666 
667  dof->m_padding1[0] = 0;
668  dof->m_padding1[1] = 0;
669  dof->m_padding1[2] = 0;
670  dof->m_padding1[3] = 0;
671 
673 }
674 
675 
676 
677 
678 
679 #endif //BT_GENERIC_6DOF_CONSTRAINT_H
void getAngularUpperLimitReversed(btVector3 &angularUpper)
void getAngularLowerLimitReversed(btVector3 &angularLower)
void setValue(const btScalar &_x, const btScalar &_y, const btScalar &_z)
Definition: btVector3.h:652
Jacobian entry is an abstraction that allows to describe constraints it can be used in combination wi...
void setLimit(int axis, btScalar lo, btScalar hi)
btGeneric6DofSpring2Constraint & operator=(btGeneric6DofSpring2Constraint &)
const btTransform & getFrameOffsetA() const
btScalar btGetMatrixElem(const btMatrix3x3 &mat, int index)
void setAngularLowerLimitReversed(const btVector3 &angularLower)
#define btAssert(x)
Definition: btScalar.h:131
const btTransform & getFrameOffsetB() const
void getLinearLowerLimit(btVector3 &linearLower)
#define SIMD_FORCE_INLINE
Definition: btScalar.h:81
btVector3 getAxis(int axis_index) const
btRotationalLimitMotor2(const btRotationalLimitMotor2 &limot)
void getAngularUpperLimit(btVector3 &angularUpper)
void getLinearUpperLimit(btVector3 &linearUpper)
btTranslationalLimitMotor2 * getTranslationalLimitMotor()
The btRigidBody is the main class for rigid body objects.
Definition: btRigidBody.h:62
void setLinearUpperLimit(const btVector3 &linearUpper)
btRotationalLimitMotor2 * getRotationalLimitMotor(int index)
this structure is not used, except for loading pre-2.82 .bullet files
void setLinearLowerLimit(const btVector3 &linearLower)
void setAngularLowerLimit(const btVector3 &angularLower)
const btTransform & getCalculatedTransformB() const
virtual void buildJacobian()
internal method used by the constraint solver, don&#39;t use them directly
btVector3 can be used to represent 3D points and vectors.
Definition: btVector3.h:83
#define ATTRIBUTE_ALIGNED16(a)
Definition: btScalar.h:82
btScalar btNormalizeAngle(btScalar angleInRadians)
Definition: btScalar.h:759
#define btGeneric6DofSpring2ConstraintDataName
bool matrixToEulerXYZ(const btMatrix3x3 &mat, btVector3 &xyz)
MatrixToEulerXYZ from http://www.geometrictools.com/LibFoundation/Mathematics/Wm4Matrix3.inl.html.
The btTransform class supports rigid transforms with only translation and rotation and no scaling/she...
Definition: btTransform.h:34
const btTransform & getCalculatedTransformA() const
TypedConstraint is the baseclass for Bullet constraints and vehicles.
virtual const char * serialize(void *dataBuffer, btSerializer *serializer) const
fills the dataBuffer and returns the struct name (and 0 on failure)
void getAngularLowerLimit(btVector3 &angularLower)
for serialization
Definition: btTransform.h:253
#define BT_DECLARE_ALIGNED_ALLOCATOR()
Definition: btScalar.h:403
virtual const char * serialize(void *dataBuffer, btSerializer *serializer) const
fills the dataBuffer and returns the struct name (and 0 on failure)
#define btGeneric6DofSpring2ConstraintData2
void setAngularUpperLimitReversed(const btVector3 &angularUpper)
The btMatrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with...
Definition: btMatrix3x3.h:48
btScalar getRelativePivotPosition(int axis_index) const
void testLimitValue(btScalar test_value)
void setAngularUpperLimit(const btVector3 &angularUpper)
void setLimitReversed(int axis, btScalar lo, btScalar hi)
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: btScalar.h:292
btTranslationalLimitMotor2(const btTranslationalLimitMotor2 &other)
btScalar getAngle(int axis_index) const