Bullet Collision Detection & Physics Library
btGeneric6DofConstraint.cpp
Go to the documentation of this file.
1/*
2Bullet Continuous Collision Detection and Physics Library
3Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org
4
5This software is provided 'as-is', without any express or implied warranty.
6In no event will the authors be held liable for any damages arising from the use of this software.
7Permission is granted to anyone to use this software for any purpose,
8including commercial applications, and to alter it and redistribute it freely,
9subject to the following restrictions:
10
111. 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.
122. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
133. This notice may not be removed or altered from any source distribution.
14*/
15/*
162007-09-09
17Refactored by Francisco Le?n
18email: projectileman@yahoo.com
19http://gimpact.sf.net
20*/
21
26#include <new>
27
28#define D6_USE_OBSOLETE_METHOD false
29#define D6_USE_FRAME_OFFSET true
30
32 : btTypedConstraint(D6_CONSTRAINT_TYPE, rbA, rbB), m_frameInA(frameInA), m_frameInB(frameInB), m_useLinearReferenceFrameA(useLinearReferenceFrameA), m_useOffsetForConstraintFrame(D6_USE_FRAME_OFFSET), m_flags(0), m_useSolveConstraintObsolete(D6_USE_OBSOLETE_METHOD)
33{
35}
36
38 : btTypedConstraint(D6_CONSTRAINT_TYPE, getFixedBody(), rbB),
39 m_frameInB(frameInB),
40 m_useLinearReferenceFrameA(useLinearReferenceFrameB),
41 m_useOffsetForConstraintFrame(D6_USE_FRAME_OFFSET),
42 m_flags(0),
43 m_useSolveConstraintObsolete(false)
44{
46 m_frameInA = rbB.getCenterOfMassTransform() * m_frameInB;
48}
49
50#define GENERIC_D6_DISABLE_WARMSTARTING 1
51
52btScalar btGetMatrixElem(const btMatrix3x3& mat, int index);
54{
55 int i = index % 3;
56 int j = index / 3;
57 return mat[i][j];
58}
59
63{
64 // // rot = cy*cz -cy*sz sy
65 // // cz*sx*sy+cx*sz cx*cz-sx*sy*sz -cy*sx
66 // // -cx*cz*sy+sx*sz cz*sx+cx*sy*sz cx*cy
67 //
68
70 if (fi < btScalar(1.0f))
71 {
72 if (fi > btScalar(-1.0f))
73 {
75 xyz[1] = btAsin(btGetMatrixElem(mat, 2));
77 return true;
78 }
79 else
80 {
81 // WARNING. Not unique. XA - ZA = -atan2(r10,r11)
83 xyz[1] = -SIMD_HALF_PI;
84 xyz[2] = btScalar(0.0);
85 return false;
86 }
87 }
88 else
89 {
90 // WARNING. Not unique. XAngle + ZAngle = atan2(r10,r11)
92 xyz[1] = SIMD_HALF_PI;
93 xyz[2] = 0.0;
94 }
95 return false;
96}
97
99
101{
102 if (m_loLimit > m_hiLimit)
103 {
104 m_currentLimit = 0; //Free from violation
105 return 0;
106 }
107 if (test_value < m_loLimit)
108 {
109 m_currentLimit = 1; //low limit violation
113 else if (m_currentLimitError < -SIMD_PI)
115 return 1;
116 }
117 else if (test_value > m_hiLimit)
118 {
119 m_currentLimit = 2; //High limit violation
123 else if (m_currentLimitError < -SIMD_PI)
125 return 2;
126 };
127
128 m_currentLimit = 0; //Free from violation
129 return 0;
130}
131
133 btScalar timeStep, btVector3& axis, btScalar jacDiagABInv,
135{
136 if (needApplyTorques() == false) return 0.0f;
137
140
141 //current error correction
142 if (m_currentLimit != 0)
143 {
146 }
147
148 maxMotorForce *= timeStep;
149
150 // current velocity difference
151
152 btVector3 angVelA = body0->getAngularVelocity();
153 btVector3 angVelB = body1->getAngularVelocity();
154
157
159
160 // correction velocity
162
164 {
165 return 0.0f; //no need for applying force
166 }
167
168 // correction impulse
170
171 // clip correction impulse
173
175 if (unclippedMotorImpulse > 0.0f)
176 {
178 }
179 else
180 {
182 }
183
184 // sort with accumulated impulses
187
190 m_accumulatedImpulse = sum > hi ? btScalar(0.) : sum < lo ? btScalar(0.) : sum;
191
193
195
196 body0->applyTorqueImpulse(motorImp);
197 body1->applyTorqueImpulse(-motorImp);
198
199 return clippedMotorImpulse;
200}
201
203
205
207{
210 if (loLimit > hiLimit)
211 {
212 m_currentLimit[limitIndex] = 0; //Free from violation
214 return 0;
215 }
216
217 if (test_value < loLimit)
218 {
219 m_currentLimit[limitIndex] = 2; //low limit violation
221 return 2;
222 }
223 else if (test_value > hiLimit)
224 {
225 m_currentLimit[limitIndex] = 1; //High limit violation
227 return 1;
228 };
229
230 m_currentLimit[limitIndex] = 0; //Free from violation
232 return 0;
233}
234
236 btScalar timeStep,
240 int limit_index,
242 const btVector3& anchorPos)
243{
245 // btVector3 rel_pos1 = pointInA - body1.getCenterOfMassPosition();
246 // btVector3 rel_pos2 = pointInB - body2.getCenterOfMassPosition();
247 btVector3 rel_pos1 = anchorPos - body1.getCenterOfMassPosition();
248 btVector3 rel_pos2 = anchorPos - body2.getCenterOfMassPosition();
249
250 btVector3 vel1 = body1.getVelocityInLocalPoint(rel_pos1);
251 btVector3 vel2 = body2.getVelocityInLocalPoint(rel_pos2);
253
255
257
258 //positional error (zeroth order error)
262
265
266 //handle the limits
267 if (minLimit < maxLimit)
268 {
269 {
270 if (depth > maxLimit)
271 {
272 depth -= maxLimit;
273 lo = btScalar(0.);
274 }
275 else
276 {
277 if (depth < minLimit)
278 {
279 depth -= minLimit;
280 hi = btScalar(0.);
281 }
282 else
283 {
284 return 0.0f;
285 }
286 }
287 }
288 }
289
291
296
298 body1.applyImpulse(impulse_vector, rel_pos1);
299 body2.applyImpulse(-impulse_vector, rel_pos2);
300
301 return normalImpulse;
302}
303
305
307{
310 // in euler angle mode we do not actually constrain the angular velocity
311 // along the axes axis[0] and axis[2] (although we do use axis[1]) :
312 //
313 // to get constrain w2-w1 along ...not
314 // ------ --------------------- ------
315 // d(angle[0])/dt = 0 ax[1] x ax[2] ax[0]
316 // d(angle[1])/dt = 0 ax[1]
317 // d(angle[2])/dt = 0 ax[0] x ax[1] ax[2]
318 //
319 // constraining w2-w1 along an axis 'a' means that a'*(w2-w1)=0.
320 // to prove the result for angle[0], write the expression for angle[0] from
321 // GetInfo1 then take the derivative. to prove this for angle[2] it is
322 // easier to take the euler rate expression for d(angle[2])/dt with respect
323 // to the components of w and set that to 0.
326
330
334}
335
337{
339}
340
342{
348 { // get weight factors depending on masses
352 btScalar miS = miA + miB;
353 if (miS > btScalar(0.f))
354 {
355 m_factA = miB / miS;
356 }
357 else
358 {
359 m_factA = btScalar(0.5f);
360 }
361 m_factB = btScalar(1.0f) - m_factA;
362 }
363}
364
367 const btVector3& pivotAInW, const btVector3& pivotBInW)
368{
378 m_rbB.getInvMass());
379}
380
383{
389}
390
392{
394 angle = btAdjustAngleToLimits(angle, m_angularLimits[axis_index].m_loLimit, m_angularLimits[axis_index].m_hiLimit);
396 //test limits
399}
400
402{
403#ifndef __SPU__
405 {
406 // Clear accumulated impulses for the next simulation step
408 int i;
409 for (i = 0; i < 3; i++)
410 {
412 }
413 //calculates transform
415
416 // const btVector3& pivotAInW = m_calculatedTransformA.getOrigin();
417 // const btVector3& pivotBInW = m_calculatedTransformB.getOrigin();
421
422 // not used here
423 // btVector3 rel_pos1 = pivotAInW - m_rbA.getCenterOfMassPosition();
424 // btVector3 rel_pos2 = pivotBInW - m_rbB.getCenterOfMassPosition();
425
427 //linear part
428 for (i = 0; i < 3; i++)
429 {
431 {
434 else
436
440 }
441 }
442
443 // angular part
444 for (i = 0; i < 3; i++)
445 {
446 //calculates error angle
448 {
449 normalWorld = this->getAxis(i);
450 // Create angular atom
452 }
453 }
454 }
455#endif //__SPU__
456}
457
459{
461 {
462 info->m_numConstraintRows = 0;
463 info->nub = 0;
464 }
465 else
466 {
467 //prepare constraint
469 info->m_numConstraintRows = 0;
470 info->nub = 6;
471 int i;
472 //test linear limits
473 for (i = 0; i < 3; i++)
474 {
476 {
477 info->m_numConstraintRows++;
478 info->nub--;
479 }
480 }
481 //test angular limits
482 for (i = 0; i < 3; i++)
483 {
485 {
486 info->m_numConstraintRows++;
487 info->nub--;
488 }
489 }
490 }
491}
492
494{
496 {
497 info->m_numConstraintRows = 0;
498 info->nub = 0;
499 }
500 else
501 {
502 //pre-allocate all 6
503 info->m_numConstraintRows = 6;
504 info->nub = 0;
505 }
506}
507
509{
511
518
520 { // for stability better to solve angular limits first
523 }
524 else
525 { // leave old version for compatibility
528 }
529}
530
532{
534 //prepare constraint
536
537 int i;
538 for (i = 0; i < 3; i++)
539 {
541 }
542
544 { // for stability better to solve angular limits first
547 }
548 else
549 { // leave old version for compatibility
552 }
553}
554
556{
557 // int row = 0;
558 //solve linear limits
560 for (int i = 0; i < 3; i++)
561 {
563 { // re-use rotational motor code
564 limot.m_bounce = btScalar(0.f);
565 limot.m_currentLimit = m_linearLimits.m_currentLimit[i];
566 limot.m_currentPosition = m_linearLimits.m_currentLinearDiff[i];
567 limot.m_currentLimitError = m_linearLimits.m_currentLimitError[i];
568 limot.m_damping = m_linearLimits.m_damping;
569 limot.m_enableMotor = m_linearLimits.m_enableMotor[i];
570 limot.m_hiLimit = m_linearLimits.m_upperLimit[i];
571 limot.m_limitSoftness = m_linearLimits.m_limitSoftness;
572 limot.m_loLimit = m_linearLimits.m_lowerLimit[i];
573 limot.m_maxLimitForce = btScalar(0.f);
574 limot.m_maxMotorForce = m_linearLimits.m_maxMotorForce[i];
575 limot.m_targetVelocity = m_linearLimits.m_targetVelocity[i];
578 limot.m_normalCFM = (flags & BT_6DOF_FLAGS_CFM_NORM) ? m_linearLimits.m_normalCFM[i] : info->cfm[0];
579 limot.m_stopCFM = (flags & BT_6DOF_FLAGS_CFM_STOP) ? m_linearLimits.m_stopCFM[i] : info->cfm[0];
580 limot.m_stopERP = (flags & BT_6DOF_FLAGS_ERP_STOP) ? m_linearLimits.m_stopERP[i] : info->erp;
582 {
583 int indx1 = (i + 1) % 3;
584 int indx2 = (i + 2) % 3;
585 int rotAllowed = 1; // rotations around orthos to current axis
586 if (m_angularLimits[indx1].m_currentLimit && m_angularLimits[indx2].m_currentLimit)
587 {
588 rotAllowed = 0;
589 }
591 }
592 else
593 {
595 }
596 }
597 }
598 return row;
599}
600
602{
604 int row = row_offset;
605 //solve angular limits
606 for (int i = 0; i < 3; i++)
607 {
608 if (d6constraint->getRotationalLimitMotor(i)->needApplyTorques())
609 {
610 btVector3 axis = d6constraint->getAxis(i);
611 int flags = m_flags >> ((i + 3) * BT_6DOF_FLAGS_AXIS_SHIFT);
613 {
614 m_angularLimits[i].m_normalCFM = info->cfm[0];
615 }
617 {
618 m_angularLimits[i].m_stopCFM = info->cfm[0];
619 }
621 {
622 m_angularLimits[i].m_stopERP = info->erp;
623 }
624 row += get_limit_motor_info2(d6constraint->getRotationalLimitMotor(i),
625 transA, transB, linVelA, linVelB, angVelA, angVelB, info, row, axis, 1);
626 }
627 }
628
629 return row;
630}
631
633{
634 (void)timeStep;
635}
636
638{
643}
644
646{
648}
649
651{
653}
654
656{
658}
659
661{
665 if (imB == btScalar(0.0))
666 {
667 weight = btScalar(1.0);
668 }
669 else
670 {
671 weight = imA / (imA + imB);
672 }
675 m_AnchorPos = pA * weight + pB * (btScalar(1.0) - weight);
676 return;
677}
678
680{
683 for (int i = 0; i < 3; i++)
684 {
687 }
688}
689
694{
695 int srow = row * info->rowskip;
696 bool powered = limot->m_enableMotor;
697 int limit = limot->m_currentLimit;
698 if (powered || limit)
699 { // if the joint is powered, or has joint limits, add in the extra row
702 J1[srow + 0] = ax1[0];
703 J1[srow + 1] = ax1[1];
704 J1[srow + 2] = ax1[2];
705
706 J2[srow + 0] = -ax1[0];
707 J2[srow + 1] = -ax1[1];
708 J2[srow + 2] = -ax1[2];
709
710 if ((!rotational))
711 {
713 {
715 // get vector from bodyB to frameB in WCS
717 // get its projection to constraint axis
719 // get vector directed from bodyB to constraint axis (and orthogonal to it)
721 // same for bodyA
725 // get desired offset between frames A and B along constraint axis
726 btScalar desiredOffs = limot->m_currentPosition - limot->m_currentLimitError;
727 // desired vector from projection of center of bodyA to projection of center of bodyB to constraint axis
729 // get offset vectors relA and relB
732 tmpA = relA.cross(ax1);
733 tmpB = relB.cross(ax1);
734 if (m_hasStaticBody && (!rotAllowed))
735 {
736 tmpA *= m_factA;
737 tmpB *= m_factB;
738 }
739 int i;
740 for (i = 0; i < 3; i++) info->m_J1angularAxis[srow + i] = tmpA[i];
741 for (i = 0; i < 3; i++) info->m_J2angularAxis[srow + i] = -tmpB[i];
742 }
743 else
744 {
745 btVector3 ltd; // Linear Torque Decoupling vector
747 ltd = c.cross(ax1);
748 info->m_J1angularAxis[srow + 0] = ltd[0];
749 info->m_J1angularAxis[srow + 1] = ltd[1];
750 info->m_J1angularAxis[srow + 2] = ltd[2];
751
752 c = m_calculatedTransformB.getOrigin() - transB.getOrigin();
753 ltd = -c.cross(ax1);
754 info->m_J2angularAxis[srow + 0] = ltd[0];
755 info->m_J2angularAxis[srow + 1] = ltd[1];
756 info->m_J2angularAxis[srow + 2] = ltd[2];
757 }
758 }
759 // if we're limited low and high simultaneously, the joint motor is
760 // ineffective
761 if (limit && (limot->m_loLimit == limot->m_hiLimit)) powered = false;
762 info->m_constraintError[srow] = btScalar(0.f);
763 if (powered)
764 {
765 info->cfm[srow] = limot->m_normalCFM;
766 if (!limit)
767 {
768 btScalar tag_vel = rotational ? limot->m_targetVelocity : -limot->m_targetVelocity;
769
770 btScalar mot_fact = getMotorFactor(limot->m_currentPosition,
771 limot->m_loLimit,
772 limot->m_hiLimit,
773 tag_vel,
774 info->fps * limot->m_stopERP);
775 info->m_constraintError[srow] += mot_fact * limot->m_targetVelocity;
776 info->m_lowerLimit[srow] = -limot->m_maxMotorForce / info->fps;
777 info->m_upperLimit[srow] = limot->m_maxMotorForce / info->fps;
778 }
779 }
780 if (limit)
781 {
782 btScalar k = info->fps * limot->m_stopERP;
783 if (!rotational)
784 {
785 info->m_constraintError[srow] += k * limot->m_currentLimitError;
786 }
787 else
788 {
789 info->m_constraintError[srow] += -k * limot->m_currentLimitError;
790 }
791 info->cfm[srow] = limot->m_stopCFM;
792 if (limot->m_loLimit == limot->m_hiLimit)
793 { // limited low and high simultaneously
796 }
797 else
798 {
799 if (limit == 1)
800 {
801 info->m_lowerLimit[srow] = 0;
803 }
804 else
805 {
807 info->m_upperLimit[srow] = 0;
808 }
809 // deal with bounce
810 if (limot->m_bounce > 0)
811 {
812 // calculate joint velocity
814 if (rotational)
815 {
816 vel = angVelA.dot(ax1);
817 //make sure that if no body -> angVelB == zero vec
818 // if (body1)
819 vel -= angVelB.dot(ax1);
820 }
821 else
822 {
823 vel = linVelA.dot(ax1);
824 //make sure that if no body -> angVelB == zero vec
825 // if (body1)
826 vel -= linVelB.dot(ax1);
827 }
828 // only apply bounce if the velocity is incoming, and if the
829 // resulting c[] exceeds what we already have.
830 if (limit == 1)
831 {
832 if (vel < 0)
833 {
834 btScalar newc = -limot->m_bounce * vel;
835 if (newc > info->m_constraintError[srow])
836 info->m_constraintError[srow] = newc;
837 }
838 }
839 else
840 {
841 if (vel > 0)
842 {
843 btScalar newc = -limot->m_bounce * vel;
844 if (newc < info->m_constraintError[srow])
845 info->m_constraintError[srow] = newc;
846 }
847 }
848 }
849 }
850 }
851 return 1;
852 }
853 else
854 return 0;
855}
856
860{
861 if ((axis >= 0) && (axis < 3))
862 {
863 switch (num)
864 {
866 m_linearLimits.m_stopERP[axis] = value;
868 break;
870 m_linearLimits.m_stopCFM[axis] = value;
872 break;
874 m_linearLimits.m_normalCFM[axis] = value;
876 break;
877 default:
879 }
880 }
881 else if ((axis >= 3) && (axis < 6))
882 {
883 switch (num)
884 {
886 m_angularLimits[axis - 3].m_stopERP = value;
888 break;
890 m_angularLimits[axis - 3].m_stopCFM = value;
892 break;
894 m_angularLimits[axis - 3].m_normalCFM = value;
896 break;
897 default:
899 }
900 }
901 else
902 {
904 }
905}
906
909{
910 btScalar retVal = 0;
911 if ((axis >= 0) && (axis < 3))
912 {
913 switch (num)
914 {
918 break;
922 break;
926 break;
927 default:
929 }
930 }
931 else if ((axis >= 3) && (axis < 6))
932 {
933 switch (num)
934 {
937 retVal = m_angularLimits[axis - 3].m_stopERP;
938 break;
941 retVal = m_angularLimits[axis - 3].m_stopCFM;
942 break;
946 break;
947 default:
949 }
950 }
951 else
952 {
954 }
955 return retVal;
956}
957
959{
962 btVector3 xAxis = yAxis.cross(zAxis); // we want right coordinate system
963
966 frameInW.getBasis().setValue(xAxis[0], yAxis[0], zAxis[0],
967 xAxis[1], yAxis[1], zAxis[1],
968 xAxis[2], yAxis[2], zAxis[2]);
969
970 // now get constraint frame in local coordinate systems
973
975}
btScalar btGetMatrixElem(const btMatrix3x3 &mat, int index)
#define D6_USE_FRAME_OFFSET
#define D6_USE_OBSOLETE_METHOD
bool matrixToEulerXYZ(const btMatrix3x3 &mat, btVector3 &xyz)
MatrixToEulerXYZ from http://www.geometrictools.com/LibFoundation/Mathematics/Wm4Matrix3....
@ BT_6DOF_FLAGS_ERP_STOP
@ BT_6DOF_FLAGS_CFM_STOP
@ BT_6DOF_FLAGS_CFM_NORM
#define BT_6DOF_FLAGS_AXIS_SHIFT
const T & btMax(const T &a, const T &b)
Definition btMinMax.h:27
btScalar dot(const btQuaternion &q1, const btQuaternion &q2)
Calculate the dot product between two quaternions.
#define SIMD_PI
Definition btScalar.h:526
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition btScalar.h:314
#define BT_LARGE_FLOAT
Definition btScalar.h:316
btScalar btAtan2(btScalar x, btScalar y)
Definition btScalar.h:518
#define SIMD_INFINITY
Definition btScalar.h:544
#define SIMD_EPSILON
Definition btScalar.h:543
btScalar btAsin(btScalar x)
Definition btScalar.h:509
#define SIMD_HALF_PI
Definition btScalar.h:528
#define SIMD_2_PI
Definition btScalar.h:527
#define btAssert(x)
Definition btScalar.h:153
static T sum(const btAlignedObjectArray< T > &items)
#define btAssertConstrParams(_par)
btScalar btAdjustAngleToLimits(btScalar angleInRadians, btScalar angleLowerLimitInRadians, btScalar angleUpperLimitInRadians)
@ BT_CONSTRAINT_CFM
@ BT_CONSTRAINT_STOP_CFM
@ BT_CONSTRAINT_STOP_ERP
@ D6_CONSTRAINT_TYPE
btGeneric6DofConstraint between two rigidbodies each with a pivotpoint that descibes the axis locatio...
btTransform m_frameInA
relative_frames
void getInfo2NonVirtual(btConstraintInfo2 *info, const btTransform &transA, const btTransform &transB, const btVector3 &linVelA, const btVector3 &linVelB, const btVector3 &angVelA, const btVector3 &angVelB)
virtual void getInfo2(btConstraintInfo2 *info)
internal method used by the constraint solver, don't use them directly
void buildLinearJacobian(btJacobianEntry &jacLinear, const btVector3 &normalWorld, const btVector3 &pivotAInW, const btVector3 &pivotBInW)
btJacobianEntry m_jacLinear[3]
Jacobians.
int setLinearLimits(btConstraintInfo2 *info, int row, const btTransform &transA, const btTransform &transB, const btVector3 &linVelA, const btVector3 &linVelB, const btVector3 &angVelA, const btVector3 &angVelB)
btGeneric6DofConstraint(btRigidBody &rbA, btRigidBody &rbB, const btTransform &frameInA, const btTransform &frameInB, bool useLinearReferenceFrameA)
btJacobianEntry m_jacAng[3]
3 orthogonal angular constraints
btScalar getRelativePivotPosition(int axis_index) const
Get the relative position of the constraint pivot.
virtual void getInfo1(btConstraintInfo1 *info)
internal method used by the constraint solver, don't use them directly
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...
btTransform m_frameInB
the constraint space w.r.t body B
int get_limit_motor_info2(btRotationalLimitMotor *limot, const btTransform &transA, const btTransform &transB, const btVector3 &linVelA, const btVector3 &linVelB, const btVector3 &angVelA, const btVector3 &angVelB, btConstraintInfo2 *info, int row, btVector3 &ax1, int rotational, int rotAllowed=false)
void updateRHS(btScalar timeStep)
virtual void buildJacobian()
performs Jacobian calculation, and also calculates angle differences and axis
void buildAngularJacobian(btJacobianEntry &jacAngular, const btVector3 &jointAxisW)
void calculateAngleInfo()
calcs the euler angles between the two bodies.
btVector3 getAxis(int axis_index) const
Get the rotation axis in global coordinates.
bool m_useSolveConstraintObsolete
for backwards compatibility during the transition to 'getInfo/getInfo2'
bool testAngularLimitMotor(int axis_index)
Test angular limit.
btScalar getAngle(int axis_index) const
Get the relative Euler angle.
void setAxis(const btVector3 &axis1, const btVector3 &axis2)
virtual btScalar getParam(int num, int axis=-1) const
return the local value of parameter
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)
btTranslationalLimitMotor m_linearLimits
Linear_Limit_parameters.
btRotationalLimitMotor m_angularLimits[3]
hinge_parameters
void setFrames(const btTransform &frameA, const btTransform &frameB)
void getInfo1NonVirtual(btConstraintInfo1 *info)
Jacobian entry is an abstraction that allows to describe constraints it can be used in combination wi...
The btMatrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with...
Definition btMatrix3x3.h:50
btMatrix3x3 inverse() const
Return the inverse of the matrix.
btMatrix3x3 transpose() const
Return the transpose of the matrix.
btVector3 getColumn(int i) const
Get a column of the matrix as a vector.
The btRigidBody is the main class for rigid body objects.
Definition btRigidBody.h:60
btScalar getInvMass() const
const btVector3 & getInvInertiaDiagLocal() const
const btTransform & getCenterOfMassTransform() const
const btVector3 & getAngularVelocity() const
const btVector3 & getCenterOfMassPosition() const
const btVector3 & getLinearVelocity() const
Rotation Limit structure for generic joints.
btScalar m_currentPosition
How much is violated this limit.
btScalar m_targetVelocity
target motor velocity
btScalar m_normalCFM
Relaxation factor.
btScalar m_maxMotorForce
max force on motor
btScalar m_bounce
restitution factor
btScalar m_loLimit
limit_parameters
btScalar m_currentLimitError
temp_variables
btScalar m_stopERP
Error tolerance factor when joint is at limit.
bool needApplyTorques() const
Need apply correction.
int testLimitValue(btScalar test_value)
calculates error
btScalar m_maxLimitForce
max force on limit
int m_currentLimit
current value of angle
btScalar solveAngularLimits(btScalar timeStep, btVector3 &axis, btScalar jacDiagABInv, btRigidBody *body0, btRigidBody *body1)
apply the correction impulses for two bodies
btScalar m_stopCFM
Constraint force mixing factor when joint is at limit.
The btTransform class supports rigid transforms with only translation and rotation and no scaling/she...
Definition btTransform.h:30
btTransform inverse() const
Return the inverse of this transform.
btMatrix3x3 & getBasis()
Return the basis matrix for the rotation.
void setIdentity()
Set this transformation to the identity.
btVector3 & getOrigin()
Return the origin vector translation.
btVector3 m_stopERP
Error tolerance factor when joint is at limit.
int m_currentLimit[3]
Current relative offset of constraint frames.
btScalar solveLinearAxis(btScalar timeStep, btScalar jacDiagABInv, btRigidBody &body1, const btVector3 &pointInA, btRigidBody &body2, const btVector3 &pointInB, int limit_index, const btVector3 &axis_normal_on_a, const btVector3 &anchorPos)
btVector3 m_stopCFM
Constraint force mixing factor when joint is at limit.
btVector3 m_maxMotorForce
max force on motor
int testLimitValue(int limitIndex, btScalar test_value)
btVector3 m_currentLinearDiff
How much is violated this limit.
btVector3 m_normalCFM
Bounce parameter for linear limit.
bool needApplyForce(int limitIndex) const
btScalar m_limitSoftness
Linear_Limit_parameters.
btVector3 m_targetVelocity
target motor velocity
btVector3 m_lowerLimit
the constraint lower limits
bool isLimited(int limitIndex) const
Test limit.
btScalar m_damping
Damping for linear limit.
btVector3 m_upperLimit
the constraint upper limits
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't use them directly
const btRigidBody & getRigidBodyA() const
const btRigidBody & getRigidBodyB() const
btVector3 can be used to represent 3D points and vectors.
Definition btVector3.h:82
btVector3 cross(const btVector3 &v) const
Return the cross product between this and another vector.
Definition btVector3.h:380
btScalar dot(const btVector3 &v) const
Return the dot product.
Definition btVector3.h:229
void setValue(const btScalar &_x, const btScalar &_y, const btScalar &_z)
Definition btVector3.h:640
btVector3 normalized() const
Return a normalized version of this vector.
Definition btVector3.h:949
btVector3 & normalize()
Normalize this vector x^2 + y^2 + z^2 = 1.
Definition btVector3.h:303