b2_wheel_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"
25 #include "box2d/b2_wheel_joint.h"
26 #include "box2d/b2_time_step.h"
27 
28 // Linear constraint (point-to-line)
29 // d = pB - pA = xB + rB - xA - rA
30 // C = dot(ay, d)
31 // Cdot = dot(d, cross(wA, ay)) + dot(ay, vB + cross(wB, rB) - vA - cross(wA, rA))
32 // = -dot(ay, vA) - dot(cross(d + rA, ay), wA) + dot(ay, vB) + dot(cross(rB, ay), vB)
33 // J = [-ay, -cross(d + rA, ay), ay, cross(rB, ay)]
34 
35 // Spring linear constraint
36 // C = dot(ax, d)
37 // Cdot = = -dot(ax, vA) - dot(cross(d + rA, ax), wA) + dot(ax, vB) + dot(cross(rB, ax), vB)
38 // J = [-ax -cross(d+rA, ax) ax cross(rB, ax)]
39 
40 // Motor rotational constraint
41 // Cdot = wB - wA
42 // J = [0 0 -1 0 0 1]
43 
44 void b2WheelJointDef::Initialize(b2Body* bA, b2Body* bB, const b2Vec2& anchor, const b2Vec2& axis)
45 {
46  bodyA = bA;
47  bodyB = bB;
48  localAnchorA = bodyA->GetLocalPoint(anchor);
49  localAnchorB = bodyB->GetLocalPoint(anchor);
51 }
52 
54 : b2Joint(def)
55 {
60 
61  m_mass = 0.0f;
62  m_impulse = 0.0f;
63  m_motorMass = 0.0f;
64  m_motorImpulse = 0.0f;
65  m_springMass = 0.0f;
66  m_springImpulse = 0.0f;
67 
68  m_axialMass = 0.0f;
69  m_lowerImpulse = 0.0f;
70  m_upperImpulse = 0.0f;
74 
76  m_motorSpeed = def->motorSpeed;
78 
79  m_bias = 0.0f;
80  m_gamma = 0.0f;
81 
82  m_ax.SetZero();
83  m_ay.SetZero();
84 
85  m_stiffness = def->stiffness;
86  m_damping = def->damping;
87 }
88 
90 {
99 
100  float mA = m_invMassA, mB = m_invMassB;
101  float iA = m_invIA, iB = m_invIB;
102 
103  b2Vec2 cA = data.positions[m_indexA].c;
104  float aA = data.positions[m_indexA].a;
105  b2Vec2 vA = data.velocities[m_indexA].v;
106  float wA = data.velocities[m_indexA].w;
107 
108  b2Vec2 cB = data.positions[m_indexB].c;
109  float aB = data.positions[m_indexB].a;
110  b2Vec2 vB = data.velocities[m_indexB].v;
111  float wB = data.velocities[m_indexB].w;
112 
113  b2Rot qA(aA), qB(aB);
114 
115  // Compute the effective masses.
118  b2Vec2 d = cB + rB - cA - rA;
119 
120  // Point to line constraint
121  {
122  m_ay = b2Mul(qA, m_localYAxisA);
123  m_sAy = b2Cross(d + rA, m_ay);
124  m_sBy = b2Cross(rB, m_ay);
125 
126  m_mass = mA + mB + iA * m_sAy * m_sAy + iB * m_sBy * m_sBy;
127 
128  if (m_mass > 0.0f)
129  {
130  m_mass = 1.0f / m_mass;
131  }
132  }
133 
134  // Spring constraint
135  m_ax = b2Mul(qA, m_localXAxisA);
136  m_sAx = b2Cross(d + rA, m_ax);
137  m_sBx = b2Cross(rB, m_ax);
138 
139  const float invMass = mA + mB + iA * m_sAx * m_sAx + iB * m_sBx * m_sBx;
140  if (invMass > 0.0f)
141  {
142  m_axialMass = 1.0f / invMass;
143  }
144  else
145  {
146  m_axialMass = 0.0f;
147  }
148 
149  m_springMass = 0.0f;
150  m_bias = 0.0f;
151  m_gamma = 0.0f;
152 
153  if (m_stiffness > 0.0f && invMass > 0.0f)
154  {
155  m_springMass = 1.0f / invMass;
156 
157  float C = b2Dot(d, m_ax);
158 
159  // magic formulas
160  float h = data.step.dt;
161  m_gamma = h * (m_damping + h * m_stiffness);
162  if (m_gamma > 0.0f)
163  {
164  m_gamma = 1.0f / m_gamma;
165  }
166 
167  m_bias = C * h * m_stiffness * m_gamma;
168 
169  m_springMass = invMass + m_gamma;
170  if (m_springMass > 0.0f)
171  {
172  m_springMass = 1.0f / m_springMass;
173  }
174  }
175  else
176  {
177  m_springImpulse = 0.0f;
178  }
179 
180  if (m_enableLimit)
181  {
182  m_translation = b2Dot(m_ax, d);
183  }
184  else
185  {
186  m_lowerImpulse = 0.0f;
187  m_upperImpulse = 0.0f;
188  }
189 
190  if (m_enableMotor)
191  {
192  m_motorMass = iA + iB;
193  if (m_motorMass > 0.0f)
194  {
195  m_motorMass = 1.0f / m_motorMass;
196  }
197  }
198  else
199  {
200  m_motorMass = 0.0f;
201  m_motorImpulse = 0.0f;
202  }
203 
204  if (data.step.warmStarting)
205  {
206  // Account for variable time step.
207  m_impulse *= data.step.dtRatio;
208  m_springImpulse *= data.step.dtRatio;
209  m_motorImpulse *= data.step.dtRatio;
210 
211  float axialImpulse = m_springImpulse + m_lowerImpulse - m_upperImpulse;
212  b2Vec2 P = m_impulse * m_ay + axialImpulse * m_ax;
213  float LA = m_impulse * m_sAy + axialImpulse * m_sAx + m_motorImpulse;
214  float LB = m_impulse * m_sBy + axialImpulse * m_sBx + m_motorImpulse;
215 
216  vA -= m_invMassA * P;
217  wA -= m_invIA * LA;
218 
219  vB += m_invMassB * P;
220  wB += m_invIB * LB;
221  }
222  else
223  {
224  m_impulse = 0.0f;
225  m_springImpulse = 0.0f;
226  m_motorImpulse = 0.0f;
227  m_lowerImpulse = 0.0f;
228  m_upperImpulse = 0.0f;
229  }
230 
231  data.velocities[m_indexA].v = vA;
232  data.velocities[m_indexA].w = wA;
233  data.velocities[m_indexB].v = vB;
234  data.velocities[m_indexB].w = wB;
235 }
236 
238 {
239  float mA = m_invMassA, mB = m_invMassB;
240  float iA = m_invIA, iB = m_invIB;
241 
242  b2Vec2 vA = data.velocities[m_indexA].v;
243  float wA = data.velocities[m_indexA].w;
244  b2Vec2 vB = data.velocities[m_indexB].v;
245  float wB = data.velocities[m_indexB].w;
246 
247  // Solve spring constraint
248  {
249  float Cdot = b2Dot(m_ax, vB - vA) + m_sBx * wB - m_sAx * wA;
250  float impulse = -m_springMass * (Cdot + m_bias + m_gamma * m_springImpulse);
251  m_springImpulse += impulse;
252 
253  b2Vec2 P = impulse * m_ax;
254  float LA = impulse * m_sAx;
255  float LB = impulse * m_sBx;
256 
257  vA -= mA * P;
258  wA -= iA * LA;
259 
260  vB += mB * P;
261  wB += iB * LB;
262  }
263 
264  // Solve rotational motor constraint
265  {
266  float Cdot = wB - wA - m_motorSpeed;
267  float impulse = -m_motorMass * Cdot;
268 
269  float oldImpulse = m_motorImpulse;
270  float maxImpulse = data.step.dt * m_maxMotorTorque;
271  m_motorImpulse = b2Clamp(m_motorImpulse + impulse, -maxImpulse, maxImpulse);
272  impulse = m_motorImpulse - oldImpulse;
273 
274  wA -= iA * impulse;
275  wB += iB * impulse;
276  }
277 
278  if (m_enableLimit)
279  {
280  // Lower limit
281  {
282  float C = m_translation - m_lowerTranslation;
283  float Cdot = b2Dot(m_ax, vB - vA) + m_sBx * wB - m_sAx * wA;
284  float impulse = -m_axialMass * (Cdot + b2Max(C, 0.0f) * data.step.inv_dt);
285  float oldImpulse = m_lowerImpulse;
286  m_lowerImpulse = b2Max(m_lowerImpulse + impulse, 0.0f);
287  impulse = m_lowerImpulse - oldImpulse;
288 
289  b2Vec2 P = impulse * m_ax;
290  float LA = impulse * m_sAx;
291  float LB = impulse * m_sBx;
292 
293  vA -= mA * P;
294  wA -= iA * LA;
295  vB += mB * P;
296  wB += iB * LB;
297  }
298 
299  // Upper limit
300  // Note: signs are flipped to keep C positive when the constraint is satisfied.
301  // This also keeps the impulse positive when the limit is active.
302  {
303  float C = m_upperTranslation - m_translation;
304  float Cdot = b2Dot(m_ax, vA - vB) + m_sAx * wA - m_sBx * wB;
305  float impulse = -m_axialMass * (Cdot + b2Max(C, 0.0f) * data.step.inv_dt);
306  float oldImpulse = m_upperImpulse;
307  m_upperImpulse = b2Max(m_upperImpulse + impulse, 0.0f);
308  impulse = m_upperImpulse - oldImpulse;
309 
310  b2Vec2 P = impulse * m_ax;
311  float LA = impulse * m_sAx;
312  float LB = impulse * m_sBx;
313 
314  vA += mA * P;
315  wA += iA * LA;
316  vB -= mB * P;
317  wB -= iB * LB;
318  }
319  }
320 
321  // Solve point to line constraint
322  {
323  float Cdot = b2Dot(m_ay, vB - vA) + m_sBy * wB - m_sAy * wA;
324  float impulse = -m_mass * Cdot;
325  m_impulse += impulse;
326 
327  b2Vec2 P = impulse * m_ay;
328  float LA = impulse * m_sAy;
329  float LB = impulse * m_sBy;
330 
331  vA -= mA * P;
332  wA -= iA * LA;
333 
334  vB += mB * P;
335  wB += iB * LB;
336  }
337 
338  data.velocities[m_indexA].v = vA;
339  data.velocities[m_indexA].w = wA;
340  data.velocities[m_indexB].v = vB;
341  data.velocities[m_indexB].w = wB;
342 }
343 
345 {
346  b2Vec2 cA = data.positions[m_indexA].c;
347  float aA = data.positions[m_indexA].a;
348  b2Vec2 cB = data.positions[m_indexB].c;
349  float aB = data.positions[m_indexB].a;
350 
351  float linearError = 0.0f;
352 
353  if (m_enableLimit)
354  {
355  b2Rot qA(aA), qB(aB);
356 
359  b2Vec2 d = (cB - cA) + rB - rA;
360 
361  b2Vec2 ax = b2Mul(qA, m_localXAxisA);
362  float sAx = b2Cross(d + rA, m_ax);
363  float sBx = b2Cross(rB, m_ax);
364 
365  float C = 0.0f;
366  float translation = b2Dot(ax, d);
368  {
369  C = translation;
370  }
371  else if (translation <= m_lowerTranslation)
372  {
373  C = b2Min(translation - m_lowerTranslation, 0.0f);
374  }
375  else if (translation >= m_upperTranslation)
376  {
377  C = b2Max(translation - m_upperTranslation, 0.0f);
378  }
379 
380  if (C != 0.0f)
381  {
382 
383  float invMass = m_invMassA + m_invMassB + m_invIA * sAx * sAx + m_invIB * sBx * sBx;
384  float impulse = 0.0f;
385  if (invMass != 0.0f)
386  {
387  impulse = -C / invMass;
388  }
389 
390  b2Vec2 P = impulse * ax;
391  float LA = impulse * sAx;
392  float LB = impulse * sBx;
393 
394  cA -= m_invMassA * P;
395  aA -= m_invIA * LA;
396  cB += m_invMassB * P;
397  aB += m_invIB * LB;
398 
399  linearError = b2Abs(C);
400  }
401  }
402 
403  // Solve perpendicular constraint
404  {
405  b2Rot qA(aA), qB(aB);
406 
409  b2Vec2 d = (cB - cA) + rB - rA;
410 
411  b2Vec2 ay = b2Mul(qA, m_localYAxisA);
412 
413  float sAy = b2Cross(d + rA, ay);
414  float sBy = b2Cross(rB, ay);
415 
416  float C = b2Dot(d, ay);
417 
418  float invMass = m_invMassA + m_invMassB + m_invIA * m_sAy * m_sAy + m_invIB * m_sBy * m_sBy;
419 
420  float impulse = 0.0f;
421  if (invMass != 0.0f)
422  {
423  impulse = - C / invMass;
424  }
425 
426  b2Vec2 P = impulse * ay;
427  float LA = impulse * sAy;
428  float LB = impulse * sBy;
429 
430  cA -= m_invMassA * P;
431  aA -= m_invIA * LA;
432  cB += m_invMassB * P;
433  aB += m_invIB * LB;
434 
435  linearError = b2Max(linearError, b2Abs(C));
436  }
437 
438  data.positions[m_indexA].c = cA;
439  data.positions[m_indexA].a = aA;
440  data.positions[m_indexB].c = cB;
441  data.positions[m_indexB].a = aB;
442 
443  return linearError <= b2_linearSlop;
444 }
445 
447 {
449 }
450 
452 {
454 }
455 
457 {
458  return inv_dt * (m_impulse * m_ay + (m_springImpulse + m_lowerImpulse - m_upperImpulse) * m_ax);
459 }
460 
461 float b2WheelJoint::GetReactionTorque(float inv_dt) const
462 {
463  return inv_dt * m_motorImpulse;
464 }
465 
467 {
468  b2Body* bA = m_bodyA;
469  b2Body* bB = m_bodyB;
470 
473  b2Vec2 d = pB - pA;
474  b2Vec2 axis = bA->GetWorldVector(m_localXAxisA);
475 
476  float translation = b2Dot(d, axis);
477  return translation;
478 }
479 
481 {
482  b2Body* bA = m_bodyA;
483  b2Body* bB = m_bodyB;
484 
487  b2Vec2 p1 = bA->m_sweep.c + rA;
488  b2Vec2 p2 = bB->m_sweep.c + rB;
489  b2Vec2 d = p2 - p1;
490  b2Vec2 axis = b2Mul(bA->m_xf.q, m_localXAxisA);
491 
492  b2Vec2 vA = bA->m_linearVelocity;
493  b2Vec2 vB = bB->m_linearVelocity;
494  float wA = bA->m_angularVelocity;
495  float wB = bB->m_angularVelocity;
496 
497  float speed = b2Dot(d, b2Cross(wA, axis)) + b2Dot(axis, vB + b2Cross(wB, rB) - vA - b2Cross(wA, rA));
498  return speed;
499 }
500 
502 {
503  b2Body* bA = m_bodyA;
504  b2Body* bB = m_bodyB;
505  return bB->m_sweep.a - bA->m_sweep.a;
506 }
507 
509 {
510  float wA = m_bodyA->m_angularVelocity;
511  float wB = m_bodyB->m_angularVelocity;
512  return wB - wA;
513 }
514 
516 {
517  return m_enableLimit;
518 }
519 
521 {
522  if (flag != m_enableLimit)
523  {
524  m_bodyA->SetAwake(true);
525  m_bodyB->SetAwake(true);
526  m_enableLimit = flag;
527  m_lowerImpulse = 0.0f;
528  m_upperImpulse = 0.0f;
529  }
530 }
531 
533 {
534  return m_lowerTranslation;
535 }
536 
538 {
539  return m_upperTranslation;
540 }
541 
542 void b2WheelJoint::SetLimits(float lower, float upper)
543 {
544  b2Assert(lower <= upper);
545  if (lower != m_lowerTranslation || upper != m_upperTranslation)
546  {
547  m_bodyA->SetAwake(true);
548  m_bodyB->SetAwake(true);
549  m_lowerTranslation = lower;
550  m_upperTranslation = upper;
551  m_lowerImpulse = 0.0f;
552  m_upperImpulse = 0.0f;
553  }
554 }
555 
557 {
558  return m_enableMotor;
559 }
560 
562 {
563  if (flag != m_enableMotor)
564  {
565  m_bodyA->SetAwake(true);
566  m_bodyB->SetAwake(true);
567  m_enableMotor = flag;
568  }
569 }
570 
572 {
573  if (speed != m_motorSpeed)
574  {
575  m_bodyA->SetAwake(true);
576  m_bodyB->SetAwake(true);
577  m_motorSpeed = speed;
578  }
579 }
580 
582 {
583  if (torque != m_maxMotorTorque)
584  {
585  m_bodyA->SetAwake(true);
586  m_bodyB->SetAwake(true);
587  m_maxMotorTorque = torque;
588  }
589 }
590 
591 float b2WheelJoint::GetMotorTorque(float inv_dt) const
592 {
593  return inv_dt * m_motorImpulse;
594 }
595 
596 void b2WheelJoint::SetStiffness(float stiffness)
597 {
598  m_stiffness = stiffness;
599 }
600 
602 {
603  return m_stiffness;
604 }
605 
606 void b2WheelJoint::SetDamping(float damping)
607 {
608  m_damping = damping;
609 }
610 
612 {
613  return m_damping;
614 }
615 
617 {
618  // FLT_DECIMAL_DIG == 9
619 
620  int32 indexA = m_bodyA->m_islandIndex;
621  int32 indexB = m_bodyB->m_islandIndex;
622 
623  b2Dump(" b2WheelJointDef jd;\n");
624  b2Dump(" jd.bodyA = bodies[%d];\n", indexA);
625  b2Dump(" jd.bodyB = bodies[%d];\n", indexB);
626  b2Dump(" jd.collideConnected = bool(%d);\n", m_collideConnected);
627  b2Dump(" jd.localAnchorA.Set(%.9g, %.9g);\n", m_localAnchorA.x, m_localAnchorA.y);
628  b2Dump(" jd.localAnchorB.Set(%.9g, %.9g);\n", m_localAnchorB.x, m_localAnchorB.y);
629  b2Dump(" jd.localAxisA.Set(%.9g, %.9g);\n", m_localXAxisA.x, m_localXAxisA.y);
630  b2Dump(" jd.enableMotor = bool(%d);\n", m_enableMotor);
631  b2Dump(" jd.motorSpeed = %.9g;\n", m_motorSpeed);
632  b2Dump(" jd.maxMotorTorque = %.9g;\n", m_maxMotorTorque);
633  b2Dump(" jd.stiffness = %.9g;\n", m_stiffness);
634  b2Dump(" jd.damping = %.9g;\n", m_damping);
635  b2Dump(" joints[%d] = m_world->CreateJoint(&jd);\n", m_index);
636 }
637 
639 void b2WheelJoint::Draw(b2Draw* draw) const
640 {
641  const b2Transform& xfA = m_bodyA->GetTransform();
642  const b2Transform& xfB = m_bodyB->GetTransform();
643  b2Vec2 pA = b2Mul(xfA, m_localAnchorA);
644  b2Vec2 pB = b2Mul(xfB, m_localAnchorB);
645 
646  b2Vec2 axis = b2Mul(xfA.q, m_localXAxisA);
647 
648  b2Color c1(0.7f, 0.7f, 0.7f);
649  b2Color c2(0.3f, 0.9f, 0.3f);
650  b2Color c3(0.9f, 0.3f, 0.3f);
651  b2Color c4(0.3f, 0.3f, 0.9f);
652  b2Color c5(0.4f, 0.4f, 0.4f);
653 
654  draw->DrawSegment(pA, pB, c5);
655 
656  if (m_enableLimit)
657  {
658  b2Vec2 lower = pA + m_lowerTranslation * axis;
659  b2Vec2 upper = pA + m_upperTranslation * axis;
660  b2Vec2 perp = b2Mul(xfA.q, m_localYAxisA);
661  draw->DrawSegment(lower, upper, c1);
662  draw->DrawSegment(lower - 0.5f * perp, lower + 0.5f * perp, c2);
663  draw->DrawSegment(upper - 0.5f * perp, upper + 0.5f * perp, c3);
664  }
665  else
666  {
667  draw->DrawSegment(pA - 1.0f * axis, pA + 1.0f * axis, c1);
668  }
669 
670  draw->DrawPoint(pA, 5.0f, c1);
671  draw->DrawPoint(pB, 5.0f, c4);
672 }
const b2Transform & GetTransform() const
Definition: b2_body.h:479
d
virtual void DrawSegment(const b2Vec2 &p1, const b2Vec2 &p2, const b2Color &color)=0
Draw a line segment.
b2WheelJoint(const b2WheelJointDef *def)
b2Velocity * velocities
Definition: b2_time_step.h:71
int32 m_islandIndex
Definition: b2_body.h:439
T b2Min(T a, T b)
Definition: b2_math.h:626
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
Definition: b2_math.h:422
void Draw(b2Draw *draw) const override
Debug draw this joint.
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
Definition: b2_math.h:395
b2Rot q
Definition: b2_math.h:361
f
b2TimeStep step
Definition: b2_time_step.h:69
void SolveVelocityConstraints(const b2SolverData &data) override
b2Vec2 m_linearVelocity
Definition: b2_body.h:444
float m_lowerTranslation
float x
Definition: b2_math.h:128
float m_motorImpulse
float y
Definition: b2_math.h:128
b2Vec2 c
Definition: b2_time_step.h:55
float lowerTranslation
The lower translation limit, usually in meters.
virtual void DrawPoint(const b2Vec2 &p, float size, const b2Color &color)=0
Draw a point.
bool m_collideConnected
Definition: b2_joint.h:188
bool IsLimitEnabled() const
Is the joint limit enabled?
void SetLimits(float lower, float upper)
Set the joint translation limits, usually in meters.
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchor, const b2Vec2 &axis)
#define b2_linearSlop
Definition: b2_common.h:65
Solver Data.
Definition: b2_time_step.h:67
void SetZero()
Set this vector to all zeros.
Definition: b2_math.h:50
b2Vec2 m_localAnchorB
int32 m_index
Definition: b2_joint.h:185
A 2D column vector.
Definition: b2_math.h:41
void SetMaxMotorTorque(float torque)
Set/Get the maximum motor force, usually in N-m.
void SetDamping(float damping)
Access damping.
float GetDamping() const
b2Vec2 c
center world positions
Definition: b2_math.h:383
signed int int32
Definition: b2_types.h:28
Color for debug drawing. Each value has the range [0,1].
Definition: b2_draw.h:30
float m_invI
Definition: b2_body.h:463
b2Vec2 localCenter
local center of mass position
Definition: b2_math.h:382
void SetMotorSpeed(float speed)
Set the motor speed, usually in radians per second.
A rigid body. These are created via b2World::CreateBody.
Definition: b2_body.h:128
b2Vec2 localAnchorA
The local anchor point relative to bodyA&#39;s origin.
float maxMotorTorque
The maximum motor torque, usually in N-m.
b2Vec2 v
Definition: b2_time_step.h:62
Definition: b2_draw.h:48
float GetUpperLimit() const
Get the upper joint translation limit, usually in meters.
float GetMotorTorque(float inv_dt) const
Get the current motor torque given the inverse time step, usually in N-m.
float GetJointTranslation() const
Get the current joint translation, usually in meters.
void SetStiffness(float stiffness)
Access spring stiffness.
b2Vec2 localAxisA
The local translation axis in bodyA.
b2Vec2 m_localCenterA
T b2Max(T a, T b)
Definition: b2_math.h:637
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
b2Vec2 GetLocalVector(const b2Vec2 &worldVector) const
Definition: b2_body.h:576
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
bool enableMotor
Enable/disable the joint motor.
b2Vec2 GetWorldVector(const b2Vec2 &localVector) const
Definition: b2_body.h:566
float GetJointAngle() const
Get the current joint angle in radians.
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
float m_upperImpulse
float m_springImpulse
b2Body * m_bodyA
Definition: b2_joint.h:182
float GetReactionTorque(float inv_dt) const override
Get the reaction torque on bodyB in N*m.
T b2Clamp(T a, T low, T high)
Definition: b2_math.h:648
float m_lowerImpulse
b2Vec2 m_localYAxisA
b2Vec2 m_localAnchorA
bool enableLimit
Enable/disable the joint limit.
bool SolvePositionConstraints(const b2SolverData &data) override
float GetJointLinearSpeed() const
Get the current joint linear speed, usually in meters per second.
float GetJointAngularSpeed() const
Get the current joint angular speed in radians per second.
void Dump() override
Dump to b2Log.
bool IsMotorEnabled() const
Is the joint motor enabled?
float m_invMass
Definition: b2_body.h:460
b2Position * positions
Definition: b2_time_step.h:70
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const
Definition: b2_body.h:571
float inv_dt
Definition: b2_time_step.h:45
void b2Dump(const char *string,...)
Definition: b2_settings.cpp:57
float GetLowerLimit() const
Get the lower joint translation limit, usually in meters.
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
Definition: b2_body.h:561
float a
world angles
Definition: b2_math.h:384
float m_upperTranslation
b2Vec2 localAnchorB
The local anchor point relative to bodyB&#39;s origin.
float m_maxMotorTorque
b2Transform m_xf
Definition: b2_body.h:441
T b2Abs(T a)
Definition: b2_math.h:610
void EnableMotor(bool flag)
Enable/disable the joint motor.
bool warmStarting
Definition: b2_time_step.h:49
Rotation.
Definition: b2_math.h:287
float dtRatio
Definition: b2_time_step.h:46
void InitVelocityConstraints(const b2SolverData &data) override
b2Vec2 m_localCenterB
float motorSpeed
The desired motor speed in radians per second.
b2Vec2 GetReactionForce(float inv_dt) const override
Get the reaction force on bodyB at the joint anchor in Newtons.
b2Body * bodyA
The first attached body.
Definition: b2_joint.h:89
void EnableLimit(bool flag)
Enable/disable the joint translation limit.
float damping
Suspension damping. Typically in units of N*s/m.
float stiffness
Suspension stiffness. Typically in units N/m.
#define b2Assert(A)
Definition: b2_common.h:37
float m_angularVelocity
Definition: b2_body.h:445
void SetAwake(bool flag)
Definition: b2_body.h:638
b2Vec2 m_localXAxisA
b2Body * bodyB
The second attached body.
Definition: b2_joint.h:92
float GetStiffness() const
b2Body * m_bodyB
Definition: b2_joint.h:183
float upperTranslation
The upper translation limit, usually in meters.
b2Sweep m_sweep
Definition: b2_body.h:442


mvsim
Author(s):
autogenerated on Tue Jul 4 2023 03:08:19