b2_prismatic_joint.cpp
Go to the documentation of this file.
1 // MIT License
2 
3 // Copyright (c) 2019 Erin Catto
4 
5 // Permission is hereby granted, free of charge, to any person obtaining a copy
6 // of this software and associated documentation files (the "Software"), to deal
7 // in the Software without restriction, including without limitation the rights
8 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 // copies of the Software, and to permit persons to whom the Software is
10 // furnished to do so, subject to the following conditions:
11 
12 // The above copyright notice and this permission notice shall be included in all
13 // copies or substantial portions of the Software.
14 
15 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 // SOFTWARE.
22 
23 #include "box2d/b2_body.h"
24 #include "box2d/b2_draw.h"
26 #include "box2d/b2_time_step.h"
27 
28 // Linear constraint (point-to-line)
29 // d = p2 - p1 = x2 + r2 - x1 - r1
30 // C = dot(perp, d)
31 // Cdot = dot(d, cross(w1, perp)) + dot(perp, v2 + cross(w2, r2) - v1 - cross(w1, r1))
32 // = -dot(perp, v1) - dot(cross(d + r1, perp), w1) + dot(perp, v2) + dot(cross(r2, perp), v2)
33 // J = [-perp, -cross(d + r1, perp), perp, cross(r2,perp)]
34 //
35 // Angular constraint
36 // C = a2 - a1 + a_initial
37 // Cdot = w2 - w1
38 // J = [0 0 -1 0 0 1]
39 //
40 // K = J * invM * JT
41 //
42 // J = [-a -s1 a s2]
43 // [0 -1 0 1]
44 // a = perp
45 // s1 = cross(d + r1, a) = cross(p2 - x1, a)
46 // s2 = cross(r2, a) = cross(p2 - x2, a)
47 
48 // Motor/Limit linear constraint
49 // C = dot(ax1, d)
50 // Cdot = -dot(ax1, v1) - dot(cross(d + r1, ax1), w1) + dot(ax1, v2) + dot(cross(r2, ax1), v2)
51 // J = [-ax1 -cross(d+r1,ax1) ax1 cross(r2,ax1)]
52 
53 // Predictive limit is applied even when the limit is not active.
54 // Prevents a constraint speed that can lead to a constraint error in one time step.
55 // Want C2 = C1 + h * Cdot >= 0
56 // Or:
57 // Cdot + C1/h >= 0
58 // I do not apply a negative constraint error because that is handled in position correction.
59 // So:
60 // Cdot + max(C1, 0)/h >= 0
61 
62 // Block Solver
63 // We develop a block solver that includes the angular and linear constraints. This makes the limit stiffer.
64 //
65 // The Jacobian has 2 rows:
66 // J = [-uT -s1 uT s2] // linear
67 // [0 -1 0 1] // angular
68 //
69 // u = perp
70 // s1 = cross(d + r1, u), s2 = cross(r2, u)
71 // a1 = cross(d + r1, v), a2 = cross(r2, v)
72 
73 void b2PrismaticJointDef::Initialize(b2Body* bA, b2Body* bB, const b2Vec2& anchor, const b2Vec2& axis)
74 {
75  bodyA = bA;
76  bodyB = bB;
77  localAnchorA = bodyA->GetLocalPoint(anchor);
78  localAnchorB = bodyB->GetLocalPoint(anchor);
81 }
82 
84 : b2Joint(def)
85 {
92 
94  m_axialMass = 0.0f;
95  m_motorImpulse = 0.0f;
96  m_lowerImpulse = 0.0f;
97  m_upperImpulse = 0.0f;
98 
101 
103 
105  m_motorSpeed = def->motorSpeed;
106  m_enableLimit = def->enableLimit;
107  m_enableMotor = def->enableMotor;
108 
109  m_translation = 0.0f;
110  m_axis.SetZero();
111  m_perp.SetZero();
112 }
113 
115 {
124 
125  b2Vec2 cA = data.positions[m_indexA].c;
126  float aA = data.positions[m_indexA].a;
127  b2Vec2 vA = data.velocities[m_indexA].v;
128  float wA = data.velocities[m_indexA].w;
129 
130  b2Vec2 cB = data.positions[m_indexB].c;
131  float aB = data.positions[m_indexB].a;
132  b2Vec2 vB = data.velocities[m_indexB].v;
133  float wB = data.velocities[m_indexB].w;
134 
135  b2Rot qA(aA), qB(aB);
136 
137  // Compute the effective masses.
140  b2Vec2 d = (cB - cA) + rB - rA;
141 
142  float mA = m_invMassA, mB = m_invMassB;
143  float iA = m_invIA, iB = m_invIB;
144 
145  // Compute motor Jacobian and effective mass.
146  {
147  m_axis = b2Mul(qA, m_localXAxisA);
148  m_a1 = b2Cross(d + rA, m_axis);
149  m_a2 = b2Cross(rB, m_axis);
150 
151  m_axialMass = mA + mB + iA * m_a1 * m_a1 + iB * m_a2 * m_a2;
152  if (m_axialMass > 0.0f)
153  {
154  m_axialMass = 1.0f / m_axialMass;
155  }
156  }
157 
158  // Prismatic constraint.
159  {
160  m_perp = b2Mul(qA, m_localYAxisA);
161 
162  m_s1 = b2Cross(d + rA, m_perp);
163  m_s2 = b2Cross(rB, m_perp);
164 
165  float k11 = mA + mB + iA * m_s1 * m_s1 + iB * m_s2 * m_s2;
166  float k12 = iA * m_s1 + iB * m_s2;
167  float k22 = iA + iB;
168  if (k22 == 0.0f)
169  {
170  // For bodies with fixed rotation.
171  k22 = 1.0f;
172  }
173 
174  m_K.ex.Set(k11, k12);
175  m_K.ey.Set(k12, k22);
176  }
177 
178  if (m_enableLimit)
179  {
181  }
182  else
183  {
184  m_lowerImpulse = 0.0f;
185  m_upperImpulse = 0.0f;
186  }
187 
188  if (m_enableMotor == false)
189  {
190  m_motorImpulse = 0.0f;
191  }
192 
193  if (data.step.warmStarting)
194  {
195  // Account for variable time step.
196  m_impulse *= data.step.dtRatio;
197  m_motorImpulse *= data.step.dtRatio;
198  m_lowerImpulse *= data.step.dtRatio;
199  m_upperImpulse *= data.step.dtRatio;
200 
201  float axialImpulse = m_motorImpulse + m_lowerImpulse - m_upperImpulse;
202  b2Vec2 P = m_impulse.x * m_perp + axialImpulse * m_axis;
203  float LA = m_impulse.x * m_s1 + m_impulse.y + axialImpulse * m_a1;
204  float LB = m_impulse.x * m_s2 + m_impulse.y + axialImpulse * m_a2;
205 
206  vA -= mA * P;
207  wA -= iA * LA;
208 
209  vB += mB * P;
210  wB += iB * LB;
211  }
212  else
213  {
214  m_impulse.SetZero();
215  m_motorImpulse = 0.0f;
216  m_lowerImpulse = 0.0f;
217  m_upperImpulse = 0.0f;
218  }
219 
220  data.velocities[m_indexA].v = vA;
221  data.velocities[m_indexA].w = wA;
222  data.velocities[m_indexB].v = vB;
223  data.velocities[m_indexB].w = wB;
224 }
225 
227 {
228  b2Vec2 vA = data.velocities[m_indexA].v;
229  float wA = data.velocities[m_indexA].w;
230  b2Vec2 vB = data.velocities[m_indexB].v;
231  float wB = data.velocities[m_indexB].w;
232 
233  float mA = m_invMassA, mB = m_invMassB;
234  float iA = m_invIA, iB = m_invIB;
235 
236  // Solve linear motor constraint
237  if (m_enableMotor)
238  {
239  float Cdot = b2Dot(m_axis, vB - vA) + m_a2 * wB - m_a1 * wA;
240  float impulse = m_axialMass * (m_motorSpeed - Cdot);
241  float oldImpulse = m_motorImpulse;
242  float maxImpulse = data.step.dt * m_maxMotorForce;
243  m_motorImpulse = b2Clamp(m_motorImpulse + impulse, -maxImpulse, maxImpulse);
244  impulse = m_motorImpulse - oldImpulse;
245 
246  b2Vec2 P = impulse * m_axis;
247  float LA = impulse * m_a1;
248  float LB = impulse * m_a2;
249 
250  vA -= mA * P;
251  wA -= iA * LA;
252  vB += mB * P;
253  wB += iB * LB;
254  }
255 
256  if (m_enableLimit)
257  {
258  // Lower limit
259  {
260  float C = m_translation - m_lowerTranslation;
261  float Cdot = b2Dot(m_axis, vB - vA) + m_a2 * wB - m_a1 * wA;
262  float impulse = -m_axialMass * (Cdot + b2Max(C, 0.0f) * data.step.inv_dt);
263  float oldImpulse = m_lowerImpulse;
264  m_lowerImpulse = b2Max(m_lowerImpulse + impulse, 0.0f);
265  impulse = m_lowerImpulse - oldImpulse;
266 
267  b2Vec2 P = impulse * m_axis;
268  float LA = impulse * m_a1;
269  float LB = impulse * m_a2;
270 
271  vA -= mA * P;
272  wA -= iA * LA;
273  vB += mB * P;
274  wB += iB * LB;
275  }
276 
277  // Upper limit
278  // Note: signs are flipped to keep C positive when the constraint is satisfied.
279  // This also keeps the impulse positive when the limit is active.
280  {
281  float C = m_upperTranslation - m_translation;
282  float Cdot = b2Dot(m_axis, vA - vB) + m_a1 * wA - m_a2 * wB;
283  float impulse = -m_axialMass * (Cdot + b2Max(C, 0.0f) * data.step.inv_dt);
284  float oldImpulse = m_upperImpulse;
285  m_upperImpulse = b2Max(m_upperImpulse + impulse, 0.0f);
286  impulse = m_upperImpulse - oldImpulse;
287 
288  b2Vec2 P = impulse * m_axis;
289  float LA = impulse * m_a1;
290  float LB = impulse * m_a2;
291 
292  vA += mA * P;
293  wA += iA * LA;
294  vB -= mB * P;
295  wB -= iB * LB;
296  }
297  }
298 
299  // Solve the prismatic constraint in block form.
300  {
301  b2Vec2 Cdot;
302  Cdot.x = b2Dot(m_perp, vB - vA) + m_s2 * wB - m_s1 * wA;
303  Cdot.y = wB - wA;
304 
305  b2Vec2 df = m_K.Solve(-Cdot);
306  m_impulse += df;
307 
308  b2Vec2 P = df.x * m_perp;
309  float LA = df.x * m_s1 + df.y;
310  float LB = df.x * m_s2 + df.y;
311 
312  vA -= mA * P;
313  wA -= iA * LA;
314 
315  vB += mB * P;
316  wB += iB * LB;
317  }
318 
319  data.velocities[m_indexA].v = vA;
320  data.velocities[m_indexA].w = wA;
321  data.velocities[m_indexB].v = vB;
322  data.velocities[m_indexB].w = wB;
323 }
324 
325 // A velocity based solver computes reaction forces(impulses) using the velocity constraint solver.Under this context,
326 // the position solver is not there to resolve forces.It is only there to cope with integration error.
327 //
328 // Therefore, the pseudo impulses in the position solver do not have any physical meaning.Thus it is okay if they suck.
329 //
330 // We could take the active state from the velocity solver.However, the joint might push past the limit when the velocity
331 // solver indicates the limit is inactive.
333 {
334  b2Vec2 cA = data.positions[m_indexA].c;
335  float aA = data.positions[m_indexA].a;
336  b2Vec2 cB = data.positions[m_indexB].c;
337  float aB = data.positions[m_indexB].a;
338 
339  b2Rot qA(aA), qB(aB);
340 
341  float mA = m_invMassA, mB = m_invMassB;
342  float iA = m_invIA, iB = m_invIB;
343 
344  // Compute fresh Jacobians
347  b2Vec2 d = cB + rB - cA - rA;
348 
349  b2Vec2 axis = b2Mul(qA, m_localXAxisA);
350  float a1 = b2Cross(d + rA, axis);
351  float a2 = b2Cross(rB, axis);
352  b2Vec2 perp = b2Mul(qA, m_localYAxisA);
353 
354  float s1 = b2Cross(d + rA, perp);
355  float s2 = b2Cross(rB, perp);
356 
357  b2Vec3 impulse;
358  b2Vec2 C1;
359  C1.x = b2Dot(perp, d);
360  C1.y = aB - aA - m_referenceAngle;
361 
362  float linearError = b2Abs(C1.x);
363  float angularError = b2Abs(C1.y);
364 
365  bool active = false;
366  float C2 = 0.0f;
367  if (m_enableLimit)
368  {
369  float translation = b2Dot(axis, d);
371  {
372  C2 = translation;
373  linearError = b2Max(linearError, b2Abs(translation));
374  active = true;
375  }
376  else if (translation <= m_lowerTranslation)
377  {
378  C2 = b2Min(translation - m_lowerTranslation, 0.0f);
379  linearError = b2Max(linearError, m_lowerTranslation - translation);
380  active = true;
381  }
382  else if (translation >= m_upperTranslation)
383  {
384  C2 = b2Max(translation - m_upperTranslation, 0.0f);
385  linearError = b2Max(linearError, translation - m_upperTranslation);
386  active = true;
387  }
388  }
389 
390  if (active)
391  {
392  float k11 = mA + mB + iA * s1 * s1 + iB * s2 * s2;
393  float k12 = iA * s1 + iB * s2;
394  float k13 = iA * s1 * a1 + iB * s2 * a2;
395  float k22 = iA + iB;
396  if (k22 == 0.0f)
397  {
398  // For fixed rotation
399  k22 = 1.0f;
400  }
401  float k23 = iA * a1 + iB * a2;
402  float k33 = mA + mB + iA * a1 * a1 + iB * a2 * a2;
403 
404  b2Mat33 K;
405  K.ex.Set(k11, k12, k13);
406  K.ey.Set(k12, k22, k23);
407  K.ez.Set(k13, k23, k33);
408 
409  b2Vec3 C;
410  C.x = C1.x;
411  C.y = C1.y;
412  C.z = C2;
413 
414  impulse = K.Solve33(-C);
415  }
416  else
417  {
418  float k11 = mA + mB + iA * s1 * s1 + iB * s2 * s2;
419  float k12 = iA * s1 + iB * s2;
420  float k22 = iA + iB;
421  if (k22 == 0.0f)
422  {
423  k22 = 1.0f;
424  }
425 
426  b2Mat22 K;
427  K.ex.Set(k11, k12);
428  K.ey.Set(k12, k22);
429 
430  b2Vec2 impulse1 = K.Solve(-C1);
431  impulse.x = impulse1.x;
432  impulse.y = impulse1.y;
433  impulse.z = 0.0f;
434  }
435 
436  b2Vec2 P = impulse.x * perp + impulse.z * axis;
437  float LA = impulse.x * s1 + impulse.y + impulse.z * a1;
438  float LB = impulse.x * s2 + impulse.y + impulse.z * a2;
439 
440  cA -= mA * P;
441  aA -= iA * LA;
442  cB += mB * P;
443  aB += iB * LB;
444 
445  data.positions[m_indexA].c = cA;
446  data.positions[m_indexA].a = aA;
447  data.positions[m_indexB].c = cB;
448  data.positions[m_indexB].a = aB;
449 
450  return linearError <= b2_linearSlop && angularError <= b2_angularSlop;
451 }
452 
454 {
456 }
457 
459 {
461 }
462 
464 {
465  return inv_dt * (m_impulse.x * m_perp + (m_motorImpulse + m_lowerImpulse - m_upperImpulse) * m_axis);
466 }
467 
468 float b2PrismaticJoint::GetReactionTorque(float inv_dt) const
469 {
470  return inv_dt * m_impulse.y;
471 }
472 
474 {
477  b2Vec2 d = pB - pA;
479 
480  float translation = b2Dot(d, axis);
481  return translation;
482 }
483 
485 {
486  b2Body* bA = m_bodyA;
487  b2Body* bB = m_bodyB;
488 
491  b2Vec2 p1 = bA->m_sweep.c + rA;
492  b2Vec2 p2 = bB->m_sweep.c + rB;
493  b2Vec2 d = p2 - p1;
494  b2Vec2 axis = b2Mul(bA->m_xf.q, m_localXAxisA);
495 
496  b2Vec2 vA = bA->m_linearVelocity;
497  b2Vec2 vB = bB->m_linearVelocity;
498  float wA = bA->m_angularVelocity;
499  float wB = bB->m_angularVelocity;
500 
501  float speed = b2Dot(d, b2Cross(wA, axis)) + b2Dot(axis, vB + b2Cross(wB, rB) - vA - b2Cross(wA, rA));
502  return speed;
503 }
504 
506 {
507  return m_enableLimit;
508 }
509 
511 {
512  if (flag != m_enableLimit)
513  {
514  m_bodyA->SetAwake(true);
515  m_bodyB->SetAwake(true);
516  m_enableLimit = flag;
517  m_lowerImpulse = 0.0f;
518  m_upperImpulse = 0.0f;
519  }
520 }
521 
523 {
524  return m_lowerTranslation;
525 }
526 
528 {
529  return m_upperTranslation;
530 }
531 
532 void b2PrismaticJoint::SetLimits(float lower, float upper)
533 {
534  b2Assert(lower <= upper);
535  if (lower != m_lowerTranslation || upper != m_upperTranslation)
536  {
537  m_bodyA->SetAwake(true);
538  m_bodyB->SetAwake(true);
539  m_lowerTranslation = lower;
540  m_upperTranslation = upper;
541  m_lowerImpulse = 0.0f;
542  m_upperImpulse = 0.0f;
543  }
544 }
545 
547 {
548  return m_enableMotor;
549 }
550 
552 {
553  if (flag != m_enableMotor)
554  {
555  m_bodyA->SetAwake(true);
556  m_bodyB->SetAwake(true);
557  m_enableMotor = flag;
558  }
559 }
560 
562 {
563  if (speed != m_motorSpeed)
564  {
565  m_bodyA->SetAwake(true);
566  m_bodyB->SetAwake(true);
567  m_motorSpeed = speed;
568  }
569 }
570 
572 {
573  if (force != m_maxMotorForce)
574  {
575  m_bodyA->SetAwake(true);
576  m_bodyB->SetAwake(true);
577  m_maxMotorForce = force;
578  }
579 }
580 
581 float b2PrismaticJoint::GetMotorForce(float inv_dt) const
582 {
583  return inv_dt * m_motorImpulse;
584 }
585 
587 {
588  // FLT_DECIMAL_DIG == 9
589 
590  int32 indexA = m_bodyA->m_islandIndex;
591  int32 indexB = m_bodyB->m_islandIndex;
592 
593  b2Dump(" b2PrismaticJointDef jd;\n");
594  b2Dump(" jd.bodyA = bodies[%d];\n", indexA);
595  b2Dump(" jd.bodyB = bodies[%d];\n", indexB);
596  b2Dump(" jd.collideConnected = bool(%d);\n", m_collideConnected);
597  b2Dump(" jd.localAnchorA.Set(%.9g, %.9g);\n", m_localAnchorA.x, m_localAnchorA.y);
598  b2Dump(" jd.localAnchorB.Set(%.9g, %.9g);\n", m_localAnchorB.x, m_localAnchorB.y);
599  b2Dump(" jd.localAxisA.Set(%.9g, %.9g);\n", m_localXAxisA.x, m_localXAxisA.y);
600  b2Dump(" jd.referenceAngle = %.9g;\n", m_referenceAngle);
601  b2Dump(" jd.enableLimit = bool(%d);\n", m_enableLimit);
602  b2Dump(" jd.lowerTranslation = %.9g;\n", m_lowerTranslation);
603  b2Dump(" jd.upperTranslation = %.9g;\n", m_upperTranslation);
604  b2Dump(" jd.enableMotor = bool(%d);\n", m_enableMotor);
605  b2Dump(" jd.motorSpeed = %.9g;\n", m_motorSpeed);
606  b2Dump(" jd.maxMotorForce = %.9g;\n", m_maxMotorForce);
607  b2Dump(" joints[%d] = m_world->CreateJoint(&jd);\n", m_index);
608 }
609 
611 {
612  const b2Transform& xfA = m_bodyA->GetTransform();
613  const b2Transform& xfB = m_bodyB->GetTransform();
614  b2Vec2 pA = b2Mul(xfA, m_localAnchorA);
615  b2Vec2 pB = b2Mul(xfB, m_localAnchorB);
616 
617  b2Vec2 axis = b2Mul(xfA.q, m_localXAxisA);
618 
619  b2Color c1(0.7f, 0.7f, 0.7f);
620  b2Color c2(0.3f, 0.9f, 0.3f);
621  b2Color c3(0.9f, 0.3f, 0.3f);
622  b2Color c4(0.3f, 0.3f, 0.9f);
623  b2Color c5(0.4f, 0.4f, 0.4f);
624 
625  draw->DrawSegment(pA, pB, c5);
626 
627  if (m_enableLimit)
628  {
629  b2Vec2 lower = pA + m_lowerTranslation * axis;
630  b2Vec2 upper = pA + m_upperTranslation * axis;
631  b2Vec2 perp = b2Mul(xfA.q, m_localYAxisA);
632  draw->DrawSegment(lower, upper, c1);
633  draw->DrawSegment(lower - 0.5f * perp, lower + 0.5f * perp, c2);
634  draw->DrawSegment(upper - 0.5f * perp, upper + 0.5f * perp, c3);
635  }
636  else
637  {
638  draw->DrawSegment(pA - 1.0f * axis, pA + 1.0f * axis, c1);
639  }
640 
641  draw->DrawPoint(pA, 5.0f, c1);
642  draw->DrawPoint(pB, 5.0f, c4);
643 }
b2PrismaticJoint::m_lowerTranslation
float m_lowerTranslation
Definition: b2_prismatic_joint.h:176
b2Cross
float b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
Definition: b2_math.h:401
b2Joint::m_index
int32 m_index
Definition: b2_joint.h:185
b2Mat33::ey
b2Vec3 ey
Definition: b2_math.h:283
b2PrismaticJoint::m_lowerImpulse
float m_lowerImpulse
Definition: b2_prismatic_joint.h:174
b2PrismaticJoint::IsMotorEnabled
bool IsMotorEnabled() const
Is the joint motor enabled?
Definition: b2_prismatic_joint.cpp:546
b2PrismaticJoint::EnableMotor
void EnableMotor(bool flag)
Enable/disable the joint motor.
Definition: b2_prismatic_joint.cpp:551
b2Vec2::y
float y
Definition: b2_math.h:128
b2Body::m_angularVelocity
float m_angularVelocity
Definition: b2_body.h:445
b2Body::SetAwake
void SetAwake(bool flag)
Definition: b2_body.h:638
b2Vec3::z
float z
Definition: b2_math.h:167
b2PrismaticJoint::m_perp
b2Vec2 m_perp
Definition: b2_prismatic_joint.h:192
b2PrismaticJoint::Draw
void Draw(b2Draw *draw) const override
Debug draw this joint.
Definition: b2_prismatic_joint.cpp:610
b2PrismaticJoint::EnableLimit
void EnableLimit(bool flag)
Enable/disable the joint limit.
Definition: b2_prismatic_joint.cpp:510
b2PrismaticJoint::m_indexB
int32 m_indexB
Definition: b2_prismatic_joint.h:185
b2PrismaticJointDef::localAnchorA
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin.
Definition: b2_prismatic_joint.h:57
b2PrismaticJoint::m_localXAxisA
b2Vec2 m_localXAxisA
Definition: b2_prismatic_joint.h:169
b2PrismaticJoint::Dump
void Dump() override
Dump to b2Log.
Definition: b2_prismatic_joint.cpp:586
b2PrismaticJoint::GetLowerLimit
float GetLowerLimit() const
Get the lower joint limit, usually in meters.
Definition: b2_prismatic_joint.cpp:522
b2Position::c
b2Vec2 c
Definition: b2_time_step.h:55
b2Mat33::ez
b2Vec3 ez
Definition: b2_math.h:283
b2PrismaticJoint::m_enableLimit
bool m_enableLimit
Definition: b2_prismatic_joint.h:180
b2PrismaticJointDef::lowerTranslation
float lowerTranslation
The lower translation limit, usually in meters.
Definition: b2_prismatic_joint.h:72
b2PrismaticJoint::m_motorImpulse
float m_motorImpulse
Definition: b2_prismatic_joint.h:173
b2PrismaticJoint::m_indexA
int32 m_indexA
Definition: b2_prismatic_joint.h:184
b2Sweep::localCenter
b2Vec2 localCenter
local center of mass position
Definition: b2_math.h:382
b2PrismaticJoint::m_upperTranslation
float m_upperTranslation
Definition: b2_prismatic_joint.h:177
b2Vec2::Normalize
float Normalize()
Convert this vector into a unit vector. Returns the length.
Definition: b2_math.h:102
b2SolverData
Solver Data.
Definition: b2_time_step.h:67
b2Body::m_invMass
float m_invMass
Definition: b2_body.h:460
b2Mat22::ex
b2Vec2 ex
Definition: b2_math.h:241
b2Draw::DrawSegment
virtual void DrawSegment(const b2Vec2 &p1, const b2Vec2 &p2, const b2Color &color)=0
Draw a line segment.
b2Vec3
A 2D column vector with 3 elements.
Definition: b2_math.h:132
b2PrismaticJoint::m_motorSpeed
float m_motorSpeed
Definition: b2_prismatic_joint.h:179
b2Mat22
A 2-by-2 matrix. Stored in column-major order.
Definition: b2_math.h:171
b2Min
T b2Min(T a, T b)
Definition: b2_math.h:626
b2PrismaticJointDef::localAnchorB
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin.
Definition: b2_prismatic_joint.h:60
b2Body
A rigid body. These are created via b2World::CreateBody.
Definition: b2_body.h:128
b2Vec2::SetZero
void SetZero()
Set this vector to all zeros.
Definition: b2_math.h:50
b2Mul
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
Definition: b2_math.h:422
b2Dump
void b2Dump(const char *string,...)
Definition: b2_settings.cpp:57
b2Velocity::v
b2Vec2 v
Definition: b2_time_step.h:62
b2PrismaticJoint::SolvePositionConstraints
bool SolvePositionConstraints(const b2SolverData &data) override
Definition: b2_prismatic_joint.cpp:332
b2Vec2::Set
void Set(float x_, float y_)
Set this vector to some specified coordinates.
Definition: b2_math.h:53
b2PrismaticJointDef::referenceAngle
float referenceAngle
The constrained angle between the bodies: bodyB_angle - bodyA_angle.
Definition: b2_prismatic_joint.h:66
b2PrismaticJoint::m_invIA
float m_invIA
Definition: b2_prismatic_joint.h:190
b2Vec2
A 2D column vector.
Definition: b2_math.h:41
b2_prismatic_joint.h
b2PrismaticJoint::InitVelocityConstraints
void InitVelocityConstraints(const b2SolverData &data) override
Definition: b2_prismatic_joint.cpp:114
f
f
b2Max
T b2Max(T a, T b)
Definition: b2_math.h:637
b2PrismaticJoint::m_a1
float m_a1
Definition: b2_prismatic_joint.h:194
b2PrismaticJoint::m_translation
float m_translation
Definition: b2_prismatic_joint.h:196
b2PrismaticJoint::m_axialMass
float m_axialMass
Definition: b2_prismatic_joint.h:197
b2PrismaticJoint::m_invMassA
float m_invMassA
Definition: b2_prismatic_joint.h:188
b2PrismaticJoint::GetAnchorB
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
Definition: b2_prismatic_joint.cpp:458
b2Draw::DrawPoint
virtual void DrawPoint(const b2Vec2 &p, float size, const b2Color &color)=0
Draw a point.
b2Body::m_xf
b2Transform m_xf
Definition: b2_body.h:441
b2PrismaticJoint::m_localCenterB
b2Vec2 m_localCenterB
Definition: b2_prismatic_joint.h:187
b2PrismaticJoint::m_localYAxisA
b2Vec2 m_localYAxisA
Definition: b2_prismatic_joint.h:170
b2SolverData::positions
b2Position * positions
Definition: b2_time_step.h:70
b2Joint
Definition: b2_joint.h:110
b2Draw
Definition: b2_draw.h:48
b2Clamp
T b2Clamp(T a, T low, T high)
Definition: b2_math.h:648
b2PrismaticJoint::m_maxMotorForce
float m_maxMotorForce
Definition: b2_prismatic_joint.h:178
b2PrismaticJoint::m_invMassB
float m_invMassB
Definition: b2_prismatic_joint.h:189
b2Mat22::Solve
b2Vec2 Solve(const b2Vec2 &b) const
Definition: b2_math.h:227
b2Body::GetWorldVector
b2Vec2 GetWorldVector(const b2Vec2 &localVector) const
Definition: b2_body.h:566
b2Transform
Definition: b2_math.h:338
b2SolverData::step
b2TimeStep step
Definition: b2_time_step.h:69
b2PrismaticJoint::m_K
b2Mat22 m_K
Definition: b2_prismatic_joint.h:195
b2Vec3::Set
void Set(float x_, float y_, float z_)
Set this vector to some specified coordinates.
Definition: b2_math.h:144
b2PrismaticJoint::m_referenceAngle
float m_referenceAngle
Definition: b2_prismatic_joint.h:171
b2PrismaticJoint::m_s1
float m_s1
Definition: b2_prismatic_joint.h:193
b2PrismaticJoint::GetReactionTorque
float GetReactionTorque(float inv_dt) const override
Get the reaction torque on bodyB in N*m.
Definition: b2_prismatic_joint.cpp:468
b2Vec3::y
float y
Definition: b2_math.h:167
b2PrismaticJoint::SetLimits
void SetLimits(float lower, float upper)
Set the joint limits, usually in meters.
Definition: b2_prismatic_joint.cpp:532
b2PrismaticJoint::m_enableMotor
bool m_enableMotor
Definition: b2_prismatic_joint.h:181
b2PrismaticJoint::m_localAnchorA
b2Vec2 m_localAnchorA
Definition: b2_prismatic_joint.h:167
b2SolverData::velocities
b2Velocity * velocities
Definition: b2_time_step.h:71
b2_draw.h
b2Dot
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
Definition: b2_math.h:395
b2Joint::m_collideConnected
bool m_collideConnected
Definition: b2_joint.h:188
b2PrismaticJoint::m_localCenterA
b2Vec2 m_localCenterA
Definition: b2_prismatic_joint.h:186
b2Color
Color for debug drawing. Each value has the range [0,1].
Definition: b2_draw.h:30
b2TimeStep::dt
float dt
Definition: b2_time_step.h:44
d
d
b2_angularSlop
#define b2_angularSlop
Definition: b2_common.h:69
b2PrismaticJointDef::enableLimit
bool enableLimit
Enable/disable the joint limit.
Definition: b2_prismatic_joint.h:69
b2PrismaticJointDef
Definition: b2_prismatic_joint.h:35
b2TimeStep::inv_dt
float inv_dt
Definition: b2_time_step.h:45
b2Body::GetLocalPoint
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const
Definition: b2_body.h:571
b2Vec2::x
float x
Definition: b2_math.h:128
b2Body::m_islandIndex
int32 m_islandIndex
Definition: b2_body.h:439
b2Mat33::Solve33
b2Vec3 Solve33(const b2Vec3 &b) const
Definition: b2_math.cpp:29
b2Body::GetLocalVector
b2Vec2 GetLocalVector(const b2Vec2 &worldVector) const
Definition: b2_body.h:576
b2Velocity::w
float w
Definition: b2_time_step.h:63
b2Transform::q
b2Rot q
Definition: b2_math.h:361
b2PrismaticJoint::GetAnchorA
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
Definition: b2_prismatic_joint.cpp:453
b2Body::GetAngle
float GetAngle() const
Definition: b2_body.h:489
b2PrismaticJoint::m_axis
b2Vec2 m_axis
Definition: b2_prismatic_joint.h:192
b2PrismaticJoint::m_s2
float m_s2
Definition: b2_prismatic_joint.h:193
b2Joint::m_bodyA
b2Body * m_bodyA
Definition: b2_joint.h:182
b2PrismaticJoint::m_impulse
b2Vec2 m_impulse
Definition: b2_prismatic_joint.h:172
b2Body::m_linearVelocity
b2Vec2 m_linearVelocity
Definition: b2_body.h:444
b2PrismaticJoint::SolveVelocityConstraints
void SolveVelocityConstraints(const b2SolverData &data) override
Definition: b2_prismatic_joint.cpp:226
b2PrismaticJoint::b2PrismaticJoint
b2PrismaticJoint(const b2PrismaticJointDef *def)
Definition: b2_prismatic_joint.cpp:83
b2Position::a
float a
Definition: b2_time_step.h:56
b2PrismaticJoint::GetJointSpeed
float GetJointSpeed() const
Get the current joint translation speed, usually in meters per second.
Definition: b2_prismatic_joint.cpp:484
b2PrismaticJointDef::upperTranslation
float upperTranslation
The upper translation limit, usually in meters.
Definition: b2_prismatic_joint.h:75
b2TimeStep::warmStarting
bool warmStarting
Definition: b2_time_step.h:49
b2_time_step.h
int32
signed int int32
Definition: b2_types.h:28
b2Mat22::ey
b2Vec2 ey
Definition: b2_math.h:241
b2Mat33
A 3-by-3 matrix. Stored in column-major order.
Definition: b2_math.h:245
b2PrismaticJoint::m_invIB
float m_invIB
Definition: b2_prismatic_joint.h:191
b2PrismaticJointDef::motorSpeed
float motorSpeed
The desired motor speed in radians per second.
Definition: b2_prismatic_joint.h:84
b2Body::m_sweep
b2Sweep m_sweep
Definition: b2_body.h:442
b2PrismaticJoint::IsLimitEnabled
bool IsLimitEnabled() const
Is the joint limit enabled?
Definition: b2_prismatic_joint.cpp:505
b2PrismaticJoint::SetMaxMotorForce
void SetMaxMotorForce(float force)
Set the maximum motor force, usually in N.
Definition: b2_prismatic_joint.cpp:571
b2Rot
Rotation.
Definition: b2_math.h:287
b2PrismaticJoint::GetMotorForce
float GetMotorForce(float inv_dt) const
Get the current motor force given the inverse time step, usually in N.
Definition: b2_prismatic_joint.cpp:581
b2PrismaticJoint::SetMotorSpeed
void SetMotorSpeed(float speed)
Set the motor speed, usually in meters per second.
Definition: b2_prismatic_joint.cpp:561
b2PrismaticJointDef::enableMotor
bool enableMotor
Enable/disable the joint motor.
Definition: b2_prismatic_joint.h:78
b2PrismaticJoint::m_upperImpulse
float m_upperImpulse
Definition: b2_prismatic_joint.h:175
b2Mat33::ex
b2Vec3 ex
Definition: b2_math.h:283
b2Sweep::c
b2Vec2 c
center world positions
Definition: b2_math.h:383
b2Assert
#define b2Assert(A)
Definition: b2_common.h:37
b2PrismaticJoint::m_localAnchorB
b2Vec2 m_localAnchorB
Definition: b2_prismatic_joint.h:168
b2PrismaticJoint::GetUpperLimit
float GetUpperLimit() const
Get the upper joint limit, usually in meters.
Definition: b2_prismatic_joint.cpp:527
b2PrismaticJoint::m_a2
float m_a2
Definition: b2_prismatic_joint.h:194
b2Body::GetWorldPoint
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
Definition: b2_body.h:561
b2Joint::m_bodyB
b2Body * m_bodyB
Definition: b2_joint.h:183
b2PrismaticJoint::GetReactionForce
b2Vec2 GetReactionForce(float inv_dt) const override
Get the reaction force on bodyB at the joint anchor in Newtons.
Definition: b2_prismatic_joint.cpp:463
b2Vec3::x
float x
Definition: b2_math.h:167
b2Body::GetTransform
const b2Transform & GetTransform() const
Definition: b2_body.h:479
b2_linearSlop
#define b2_linearSlop
Definition: b2_common.h:65
b2PrismaticJointDef::maxMotorForce
float maxMotorForce
The maximum motor torque, usually in N-m.
Definition: b2_prismatic_joint.h:81
b2PrismaticJointDef::localAxisA
b2Vec2 localAxisA
The local translation unit axis in bodyA.
Definition: b2_prismatic_joint.h:63
b2Body::m_invI
float m_invI
Definition: b2_body.h:463
b2JointDef::bodyA
b2Body * bodyA
The first attached body.
Definition: b2_joint.h:89
b2Abs
T b2Abs(T a)
Definition: b2_math.h:610
b2PrismaticJointDef::Initialize
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchor, const b2Vec2 &axis)
Definition: b2_prismatic_joint.cpp:73
b2PrismaticJoint::GetJointTranslation
float GetJointTranslation() const
Get the current joint translation, usually in meters.
Definition: b2_prismatic_joint.cpp:473
b2TimeStep::dtRatio
float dtRatio
Definition: b2_time_step.h:46
b2JointDef::bodyB
b2Body * bodyB
The second attached body.
Definition: b2_joint.h:92
b2_body.h


mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:07