b2_revolute_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 // Point-to-point constraint
29 // C = p2 - p1
30 // Cdot = v2 - v1
31 // = v2 + cross(w2, r2) - v1 - cross(w1, r1)
32 // J = [-I -r1_skew I r2_skew ]
33 // Identity used:
34 // w k % (rx i + ry j) = w * (-ry i + rx j)
35 
36 // Motor constraint
37 // Cdot = w2 - w1
38 // J = [0 0 -1 0 0 1]
39 // K = invI1 + invI2
40 
41 void b2RevoluteJointDef::Initialize(b2Body* bA, b2Body* bB, const b2Vec2& anchor)
42 {
43  bodyA = bA;
44  bodyB = bB;
45  localAnchorA = bodyA->GetLocalPoint(anchor);
46  localAnchorB = bodyB->GetLocalPoint(anchor);
48 }
49 
51 : b2Joint(def)
52 {
56 
58  m_axialMass = 0.0f;
59  m_motorImpulse = 0.0f;
60  m_lowerImpulse = 0.0f;
61  m_upperImpulse = 0.0f;
62 
63  m_lowerAngle = def->lowerAngle;
64  m_upperAngle = def->upperAngle;
66  m_motorSpeed = def->motorSpeed;
69 
70  m_angle = 0.0f;
71 }
72 
74 {
83 
84  float aA = data.positions[m_indexA].a;
85  b2Vec2 vA = data.velocities[m_indexA].v;
86  float wA = data.velocities[m_indexA].w;
87 
88  float aB = data.positions[m_indexB].a;
89  b2Vec2 vB = data.velocities[m_indexB].v;
90  float wB = data.velocities[m_indexB].w;
91 
92  b2Rot qA(aA), qB(aB);
93 
96 
97  // J = [-I -r1_skew I r2_skew]
98  // r_skew = [-ry; rx]
99 
100  // Matlab
101  // K = [ mA+r1y^2*iA+mB+r2y^2*iB, -r1y*iA*r1x-r2y*iB*r2x]
102  // [ -r1y*iA*r1x-r2y*iB*r2x, mA+r1x^2*iA+mB+r2x^2*iB]
103 
104  float mA = m_invMassA, mB = m_invMassB;
105  float iA = m_invIA, iB = m_invIB;
106 
107  m_K.ex.x = mA + mB + m_rA.y * m_rA.y * iA + m_rB.y * m_rB.y * iB;
108  m_K.ey.x = -m_rA.y * m_rA.x * iA - m_rB.y * m_rB.x * iB;
109  m_K.ex.y = m_K.ey.x;
110  m_K.ey.y = mA + mB + m_rA.x * m_rA.x * iA + m_rB.x * m_rB.x * iB;
111 
112  m_axialMass = iA + iB;
113  bool fixedRotation;
114  if (m_axialMass > 0.0f)
115  {
116  m_axialMass = 1.0f / m_axialMass;
117  fixedRotation = false;
118  }
119  else
120  {
121  fixedRotation = true;
122  }
123 
124  m_angle = aB - aA - m_referenceAngle;
125  if (m_enableLimit == false || fixedRotation)
126  {
127  m_lowerImpulse = 0.0f;
128  m_upperImpulse = 0.0f;
129  }
130 
131  if (m_enableMotor == false || fixedRotation)
132  {
133  m_motorImpulse = 0.0f;
134  }
135 
136  if (data.step.warmStarting)
137  {
138  // Scale impulses to support a variable time step.
139  m_impulse *= data.step.dtRatio;
140  m_motorImpulse *= data.step.dtRatio;
141  m_lowerImpulse *= data.step.dtRatio;
142  m_upperImpulse *= data.step.dtRatio;
143 
144  float axialImpulse = m_motorImpulse + m_lowerImpulse - m_upperImpulse;
146 
147  vA -= mA * P;
148  wA -= iA * (b2Cross(m_rA, P) + axialImpulse);
149 
150  vB += mB * P;
151  wB += iB * (b2Cross(m_rB, P) + axialImpulse);
152  }
153  else
154  {
155  m_impulse.SetZero();
156  m_motorImpulse = 0.0f;
157  m_lowerImpulse = 0.0f;
158  m_upperImpulse = 0.0f;
159  }
160 
161  data.velocities[m_indexA].v = vA;
162  data.velocities[m_indexA].w = wA;
163  data.velocities[m_indexB].v = vB;
164  data.velocities[m_indexB].w = wB;
165 }
166 
168 {
169  b2Vec2 vA = data.velocities[m_indexA].v;
170  float wA = data.velocities[m_indexA].w;
171  b2Vec2 vB = data.velocities[m_indexB].v;
172  float wB = data.velocities[m_indexB].w;
173 
174  float mA = m_invMassA, mB = m_invMassB;
175  float iA = m_invIA, iB = m_invIB;
176 
177  bool fixedRotation = (iA + iB == 0.0f);
178 
179  // Solve motor constraint.
180  if (m_enableMotor && fixedRotation == false)
181  {
182  float Cdot = wB - wA - m_motorSpeed;
183  float impulse = -m_axialMass * Cdot;
184  float oldImpulse = m_motorImpulse;
185  float maxImpulse = data.step.dt * m_maxMotorTorque;
186  m_motorImpulse = b2Clamp(m_motorImpulse + impulse, -maxImpulse, maxImpulse);
187  impulse = m_motorImpulse - oldImpulse;
188 
189  wA -= iA * impulse;
190  wB += iB * impulse;
191  }
192 
193  if (m_enableLimit && fixedRotation == false)
194  {
195  // Lower limit
196  {
197  float C = m_angle - m_lowerAngle;
198  float Cdot = wB - wA;
199  float impulse = -m_axialMass * (Cdot + b2Max(C, 0.0f) * data.step.inv_dt);
200  float oldImpulse = m_lowerImpulse;
201  m_lowerImpulse = b2Max(m_lowerImpulse + impulse, 0.0f);
202  impulse = m_lowerImpulse - oldImpulse;
203 
204  wA -= iA * impulse;
205  wB += iB * impulse;
206  }
207 
208  // Upper limit
209  // Note: signs are flipped to keep C positive when the constraint is satisfied.
210  // This also keeps the impulse positive when the limit is active.
211  {
212  float C = m_upperAngle - m_angle;
213  float Cdot = wA - wB;
214  float impulse = -m_axialMass * (Cdot + b2Max(C, 0.0f) * data.step.inv_dt);
215  float oldImpulse = m_upperImpulse;
216  m_upperImpulse = b2Max(m_upperImpulse + impulse, 0.0f);
217  impulse = m_upperImpulse - oldImpulse;
218 
219  wA += iA * impulse;
220  wB -= iB * impulse;
221  }
222  }
223 
224  // Solve point-to-point constraint
225  {
226  b2Vec2 Cdot = vB + b2Cross(wB, m_rB) - vA - b2Cross(wA, m_rA);
227  b2Vec2 impulse = m_K.Solve(-Cdot);
228 
229  m_impulse.x += impulse.x;
230  m_impulse.y += impulse.y;
231 
232  vA -= mA * impulse;
233  wA -= iA * b2Cross(m_rA, impulse);
234 
235  vB += mB * impulse;
236  wB += iB * b2Cross(m_rB, impulse);
237  }
238 
239  data.velocities[m_indexA].v = vA;
240  data.velocities[m_indexA].w = wA;
241  data.velocities[m_indexB].v = vB;
242  data.velocities[m_indexB].w = wB;
243 }
244 
246 {
247  b2Vec2 cA = data.positions[m_indexA].c;
248  float aA = data.positions[m_indexA].a;
249  b2Vec2 cB = data.positions[m_indexB].c;
250  float aB = data.positions[m_indexB].a;
251 
252  b2Rot qA(aA), qB(aB);
253 
254  float angularError = 0.0f;
255  float positionError = 0.0f;
256 
257  bool fixedRotation = (m_invIA + m_invIB == 0.0f);
258 
259  // Solve angular limit constraint
260  if (m_enableLimit && fixedRotation == false)
261  {
262  float angle = aB - aA - m_referenceAngle;
263  float C = 0.0f;
264 
266  {
267  // Prevent large angular corrections
269  }
270  else if (angle <= m_lowerAngle)
271  {
272  // Prevent large angular corrections and allow some slop.
274  }
275  else if (angle >= m_upperAngle)
276  {
277  // Prevent large angular corrections and allow some slop.
279  }
280 
281  float limitImpulse = -m_axialMass * C;
282  aA -= m_invIA * limitImpulse;
283  aB += m_invIB * limitImpulse;
284  angularError = b2Abs(C);
285  }
286 
287  // Solve point-to-point constraint.
288  {
289  qA.Set(aA);
290  qB.Set(aB);
293 
294  b2Vec2 C = cB + rB - cA - rA;
295  positionError = C.Length();
296 
297  float mA = m_invMassA, mB = m_invMassB;
298  float iA = m_invIA, iB = m_invIB;
299 
300  b2Mat22 K;
301  K.ex.x = mA + mB + iA * rA.y * rA.y + iB * rB.y * rB.y;
302  K.ex.y = -iA * rA.x * rA.y - iB * rB.x * rB.y;
303  K.ey.x = K.ex.y;
304  K.ey.y = mA + mB + iA * rA.x * rA.x + iB * rB.x * rB.x;
305 
306  b2Vec2 impulse = -K.Solve(C);
307 
308  cA -= mA * impulse;
309  aA -= iA * b2Cross(rA, impulse);
310 
311  cB += mB * impulse;
312  aB += iB * b2Cross(rB, impulse);
313  }
314 
315  data.positions[m_indexA].c = cA;
316  data.positions[m_indexA].a = aA;
317  data.positions[m_indexB].c = cB;
318  data.positions[m_indexB].a = aB;
319 
320  return positionError <= b2_linearSlop && angularError <= b2_angularSlop;
321 }
322 
324 {
326 }
327 
329 {
331 }
332 
334 {
336  return inv_dt * P;
337 }
338 
339 float b2RevoluteJoint::GetReactionTorque(float inv_dt) const
340 {
341  return inv_dt * (m_motorImpulse + m_lowerImpulse - m_upperImpulse);
342 }
343 
345 {
346  b2Body* bA = m_bodyA;
347  b2Body* bB = m_bodyB;
348  return bB->m_sweep.a - bA->m_sweep.a - m_referenceAngle;
349 }
350 
352 {
353  b2Body* bA = m_bodyA;
354  b2Body* bB = m_bodyB;
355  return bB->m_angularVelocity - bA->m_angularVelocity;
356 }
357 
359 {
360  return m_enableMotor;
361 }
362 
364 {
365  if (flag != m_enableMotor)
366  {
367  m_bodyA->SetAwake(true);
368  m_bodyB->SetAwake(true);
369  m_enableMotor = flag;
370  }
371 }
372 
373 float b2RevoluteJoint::GetMotorTorque(float inv_dt) const
374 {
375  return inv_dt * m_motorImpulse;
376 }
377 
379 {
380  if (speed != m_motorSpeed)
381  {
382  m_bodyA->SetAwake(true);
383  m_bodyB->SetAwake(true);
384  m_motorSpeed = speed;
385  }
386 }
387 
389 {
390  if (torque != m_maxMotorTorque)
391  {
392  m_bodyA->SetAwake(true);
393  m_bodyB->SetAwake(true);
394  m_maxMotorTorque = torque;
395  }
396 }
397 
399 {
400  return m_enableLimit;
401 }
402 
404 {
405  if (flag != m_enableLimit)
406  {
407  m_bodyA->SetAwake(true);
408  m_bodyB->SetAwake(true);
409  m_enableLimit = flag;
410  m_lowerImpulse = 0.0f;
411  m_upperImpulse = 0.0f;
412  }
413 }
414 
416 {
417  return m_lowerAngle;
418 }
419 
421 {
422  return m_upperAngle;
423 }
424 
425 void b2RevoluteJoint::SetLimits(float lower, float upper)
426 {
427  b2Assert(lower <= upper);
428 
429  if (lower != m_lowerAngle || upper != m_upperAngle)
430  {
431  m_bodyA->SetAwake(true);
432  m_bodyB->SetAwake(true);
433  m_lowerImpulse = 0.0f;
434  m_upperImpulse = 0.0f;
435  m_lowerAngle = lower;
436  m_upperAngle = upper;
437  }
438 }
439 
441 {
442  int32 indexA = m_bodyA->m_islandIndex;
443  int32 indexB = m_bodyB->m_islandIndex;
444 
445  b2Dump(" b2RevoluteJointDef jd;\n");
446  b2Dump(" jd.bodyA = bodies[%d];\n", indexA);
447  b2Dump(" jd.bodyB = bodies[%d];\n", indexB);
448  b2Dump(" jd.collideConnected = bool(%d);\n", m_collideConnected);
449  b2Dump(" jd.localAnchorA.Set(%.9g, %.9g);\n", m_localAnchorA.x, m_localAnchorA.y);
450  b2Dump(" jd.localAnchorB.Set(%.9g, %.9g);\n", m_localAnchorB.x, m_localAnchorB.y);
451  b2Dump(" jd.referenceAngle = %.9g;\n", m_referenceAngle);
452  b2Dump(" jd.enableLimit = bool(%d);\n", m_enableLimit);
453  b2Dump(" jd.lowerAngle = %.9g;\n", m_lowerAngle);
454  b2Dump(" jd.upperAngle = %.9g;\n", m_upperAngle);
455  b2Dump(" jd.enableMotor = bool(%d);\n", m_enableMotor);
456  b2Dump(" jd.motorSpeed = %.9g;\n", m_motorSpeed);
457  b2Dump(" jd.maxMotorTorque = %.9g;\n", m_maxMotorTorque);
458  b2Dump(" joints[%d] = m_world->CreateJoint(&jd);\n", m_index);
459 }
460 
462 void b2RevoluteJoint::Draw(b2Draw* draw) const
463 {
464  const b2Transform& xfA = m_bodyA->GetTransform();
465  const b2Transform& xfB = m_bodyB->GetTransform();
466  b2Vec2 pA = b2Mul(xfA, m_localAnchorA);
467  b2Vec2 pB = b2Mul(xfB, m_localAnchorB);
468 
469  b2Color c1(0.7f, 0.7f, 0.7f);
470  b2Color c2(0.3f, 0.9f, 0.3f);
471  b2Color c3(0.9f, 0.3f, 0.3f);
472  b2Color c4(0.3f, 0.3f, 0.9f);
473  b2Color c5(0.4f, 0.4f, 0.4f);
474 
475  draw->DrawPoint(pA, 5.0f, c4);
476  draw->DrawPoint(pB, 5.0f, c5);
477 
478  float aA = m_bodyA->GetAngle();
479  float aB = m_bodyB->GetAngle();
480  float angle = aB - aA - m_referenceAngle;
481 
482  const float L = 0.5f;
483 
484  b2Vec2 r = L * b2Vec2(cosf(angle), sinf(angle));
485  draw->DrawSegment(pB, pB + r, c1);
486  draw->DrawCircle(pB, L, c1);
487 
488  if (m_enableLimit)
489  {
490  b2Vec2 rlo = L * b2Vec2(cosf(m_lowerAngle), sinf(m_lowerAngle));
491  b2Vec2 rhi = L * b2Vec2(cosf(m_upperAngle), sinf(m_upperAngle));
492 
493  draw->DrawSegment(pB, pB + rlo, c2);
494  draw->DrawSegment(pB, pB + rhi, c3);
495  }
496 
497  b2Color color(0.5f, 0.8f, 0.8f);
498  draw->DrawSegment(xfA.p, pA, color);
499  draw->DrawSegment(pA, pB, color);
500  draw->DrawSegment(xfB.p, pB, color);
501 }
const b2Transform & GetTransform() const
Definition: b2_body.h:479
virtual void DrawSegment(const b2Vec2 &p1, const b2Vec2 &p2, const b2Color &color)=0
Draw a line segment.
b2Velocity * velocities
Definition: b2_time_step.h:71
int32 m_islandIndex
Definition: b2_body.h:439
virtual void DrawCircle(const b2Vec2 &center, float radius, const b2Color &color)=0
Draw a circle.
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
Definition: b2_math.h:422
b2Vec2 localAnchorB
The local anchor point relative to bodyB&#39;s origin.
float lowerAngle
The lower angle for the joint limit (radians).
b2Vec2 p
Definition: b2_math.h:360
b2Vec2 Solve(const b2Vec2 &b) const
Definition: b2_math.h:227
void SetMotorSpeed(float speed)
Set the motor speed in radians per second.
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
f
bool IsMotorEnabled() const
Is the joint motor enabled?
b2TimeStep step
Definition: b2_time_step.h:69
#define b2_maxAngularCorrection
Definition: b2_common.h:91
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchor)
float Length() const
Get the length of this vector (the norm).
Definition: b2_math.h:89
float x
Definition: b2_math.h:128
float y
Definition: b2_math.h:128
b2Vec2 c
Definition: b2_time_step.h:55
float GetMotorTorque(float inv_dt) const
void SetLimits(float lower, float upper)
Set the joint limits in radians.
virtual void DrawPoint(const b2Vec2 &p, float size, const b2Color &color)=0
Draw a point.
bool m_collideConnected
Definition: b2_joint.h:188
void SolveVelocityConstraints(const b2SolverData &data) override
void SetMaxMotorTorque(float torque)
Set the maximum motor torque, usually in N-m.
#define b2_linearSlop
Definition: b2_common.h:65
#define b2_angularSlop
Definition: b2_common.h:69
Solver Data.
Definition: b2_time_step.h:67
void SetZero()
Set this vector to all zeros.
Definition: b2_math.h:50
int32 m_index
Definition: b2_joint.h:185
A 2D column vector.
Definition: b2_math.h:41
void Draw(b2Draw *draw) const override
Debug draw this joint.
b2Vec2 ey
Definition: b2_math.h:241
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 EnableMotor(bool flag)
Enable/disable the joint motor.
float GetReactionTorque(float inv_dt) const override
A rigid body. These are created via b2World::CreateBody.
Definition: b2_body.h:128
b2Vec2 v
Definition: b2_time_step.h:62
Definition: b2_draw.h:48
float GetJointSpeed() const
Get the current joint angle speed in radians per second.
float GetJointAngle() const
Get the current joint angle in radians.
b2Vec2 localAnchorA
The local anchor point relative to bodyA&#39;s origin.
T b2Max(T a, T b)
Definition: b2_math.h:637
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
float referenceAngle
The bodyB angle minus bodyA angle in the reference state (radians).
bool IsLimitEnabled() const
Is the joint limit enabled?
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
bool SolvePositionConstraints(const b2SolverData &data) override
float GetAngle() const
Definition: b2_body.h:489
b2Body * m_bodyA
Definition: b2_joint.h:182
bool enableMotor
A flag to enable the joint motor.
float GetUpperLimit() const
Get the upper joint limit in radians.
T b2Clamp(T a, T low, T high)
Definition: b2_math.h:648
b2RevoluteJoint(const b2RevoluteJointDef *def)
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
b2Vec2 GetReactionForce(float inv_dt) const override
float motorSpeed
The desired motor speed. Usually in radians per second.
float m_invMass
Definition: b2_body.h:460
b2Position * positions
Definition: b2_time_step.h:70
float upperAngle
The upper angle for the joint limit (radians).
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
void InitVelocityConstraints(const b2SolverData &data) override
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
Definition: b2_body.h:561
float a
world angles
Definition: b2_math.h:384
b2Vec2 ex
Definition: b2_math.h:241
A 2-by-2 matrix. Stored in column-major order.
Definition: b2_math.h:171
bool enableLimit
A flag to enable joint limits.
T b2Abs(T a)
Definition: b2_math.h:610
void EnableLimit(bool flag)
Enable/disable the joint limit.
bool warmStarting
Definition: b2_time_step.h:49
Rotation.
Definition: b2_math.h:287
float dtRatio
Definition: b2_time_step.h:46
b2Body * bodyA
The first attached body.
Definition: b2_joint.h:89
#define b2Assert(A)
Definition: b2_common.h:37
void Dump() override
Dump to b2Log.
float m_angularVelocity
Definition: b2_body.h:445
float GetLowerLimit() const
Get the lower joint limit in radians.
void SetAwake(bool flag)
Definition: b2_body.h:638
b2Body * bodyB
The second attached body.
Definition: b2_joint.h:92
b2Body * m_bodyB
Definition: b2_joint.h:183
b2Sweep m_sweep
Definition: b2_body.h:442
void Set(float angle)
Set using an angle in radians.
Definition: b2_math.h:300


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