b2_distance_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 // 1-D constrained system
29 // m (v2 - v1) = lambda
30 // v2 + (beta/h) * x1 + gamma * lambda = 0, gamma has units of inverse mass.
31 // x2 = x1 + h * v2
32 
33 // 1-D mass-damper-spring system
34 // m (v2 - v1) + h * d * v2 + h * k *
35 
36 // C = norm(p2 - p1) - L
37 // u = (p2 - p1) / norm(p2 - p1)
38 // Cdot = dot(u, v2 + cross(w2, r2) - v1 - cross(w1, r1))
39 // J = [-u -cross(r1, u) u cross(r2, u)]
40 // K = J * invM * JT
41 // = invMass1 + invI1 * cross(r1, u)^2 + invMass2 + invI2 * cross(r2, u)^2
42 
43 
45  const b2Vec2& anchor1, const b2Vec2& anchor2)
46 {
47  bodyA = b1;
48  bodyB = b2;
49  localAnchorA = bodyA->GetLocalPoint(anchor1);
50  localAnchorB = bodyB->GetLocalPoint(anchor2);
51  b2Vec2 d = anchor2 - anchor1;
53  minLength = length;
54  maxLength = length;
55 }
56 
58 : b2Joint(def)
59 {
65  m_stiffness = def->stiffness;
66  m_damping = def->damping;
67 
68  m_gamma = 0.0f;
69  m_bias = 0.0f;
70  m_impulse = 0.0f;
71  m_lowerImpulse = 0.0f;
72  m_upperImpulse = 0.0f;
73  m_currentLength = 0.0f;
74 }
75 
77 {
86 
87  b2Vec2 cA = data.positions[m_indexA].c;
88  float aA = data.positions[m_indexA].a;
89  b2Vec2 vA = data.velocities[m_indexA].v;
90  float wA = data.velocities[m_indexA].w;
91 
92  b2Vec2 cB = data.positions[m_indexB].c;
93  float aB = data.positions[m_indexB].a;
94  b2Vec2 vB = data.velocities[m_indexB].v;
95  float wB = data.velocities[m_indexB].w;
96 
97  b2Rot qA(aA), qB(aB);
98 
101  m_u = cB + m_rB - cA - m_rA;
102 
103  // Handle singularity.
106  {
107  m_u *= 1.0f / m_currentLength;
108  }
109  else
110  {
111  m_u.Set(0.0f, 0.0f);
112  m_mass = 0.0f;
113  m_impulse = 0.0f;
114  m_lowerImpulse = 0.0f;
115  m_upperImpulse = 0.0f;
116  }
117 
118  float crAu = b2Cross(m_rA, m_u);
119  float crBu = b2Cross(m_rB, m_u);
120  float invMass = m_invMassA + m_invIA * crAu * crAu + m_invMassB + m_invIB * crBu * crBu;
121  m_mass = invMass != 0.0f ? 1.0f / invMass : 0.0f;
122 
123  if (m_stiffness > 0.0f && m_minLength < m_maxLength)
124  {
125  // soft
126  float C = m_currentLength - m_length;
127 
128  float d = m_damping;
129  float k = m_stiffness;
130 
131  // magic formulas
132  float h = data.step.dt;
133 
134  // gamma = 1 / (h * (d + h * k))
135  // the extra factor of h in the denominator is since the lambda is an impulse, not a force
136  m_gamma = h * (d + h * k);
137  m_gamma = m_gamma != 0.0f ? 1.0f / m_gamma : 0.0f;
138  m_bias = C * h * k * m_gamma;
139 
140  invMass += m_gamma;
141  m_softMass = invMass != 0.0f ? 1.0f / invMass : 0.0f;
142  }
143  else
144  {
145  // rigid
146  m_gamma = 0.0f;
147  m_bias = 0.0f;
148  m_softMass = m_mass;
149  }
150 
151  if (data.step.warmStarting)
152  {
153  // Scale the impulse to support a variable time step.
154  m_impulse *= data.step.dtRatio;
155  m_lowerImpulse *= data.step.dtRatio;
156  m_upperImpulse *= data.step.dtRatio;
157 
159  vA -= m_invMassA * P;
160  wA -= m_invIA * b2Cross(m_rA, P);
161  vB += m_invMassB * P;
162  wB += m_invIB * b2Cross(m_rB, P);
163  }
164  else
165  {
166  m_impulse = 0.0f;
167  }
168 
169  data.velocities[m_indexA].v = vA;
170  data.velocities[m_indexA].w = wA;
171  data.velocities[m_indexB].v = vB;
172  data.velocities[m_indexB].w = wB;
173 }
174 
176 {
177  b2Vec2 vA = data.velocities[m_indexA].v;
178  float wA = data.velocities[m_indexA].w;
179  b2Vec2 vB = data.velocities[m_indexB].v;
180  float wB = data.velocities[m_indexB].w;
181 
182  if (m_minLength < m_maxLength)
183  {
184  if (m_stiffness > 0.0f)
185  {
186  // Cdot = dot(u, v + cross(w, r))
187  b2Vec2 vpA = vA + b2Cross(wA, m_rA);
188  b2Vec2 vpB = vB + b2Cross(wB, m_rB);
189  float Cdot = b2Dot(m_u, vpB - vpA);
190 
191  float impulse = -m_softMass * (Cdot + m_bias + m_gamma * m_impulse);
192  m_impulse += impulse;
193 
194  b2Vec2 P = impulse * m_u;
195  vA -= m_invMassA * P;
196  wA -= m_invIA * b2Cross(m_rA, P);
197  vB += m_invMassB * P;
198  wB += m_invIB * b2Cross(m_rB, P);
199  }
200 
201  // lower
202  {
203  float C = m_currentLength - m_minLength;
204  float bias = b2Max(0.0f, C) * data.step.inv_dt;
205 
206  b2Vec2 vpA = vA + b2Cross(wA, m_rA);
207  b2Vec2 vpB = vB + b2Cross(wB, m_rB);
208  float Cdot = b2Dot(m_u, vpB - vpA);
209 
210  float impulse = -m_mass * (Cdot + bias);
211  float oldImpulse = m_lowerImpulse;
212  m_lowerImpulse = b2Max(0.0f, m_lowerImpulse + impulse);
213  impulse = m_lowerImpulse - oldImpulse;
214  b2Vec2 P = impulse * m_u;
215 
216  vA -= m_invMassA * P;
217  wA -= m_invIA * b2Cross(m_rA, P);
218  vB += m_invMassB * P;
219  wB += m_invIB * b2Cross(m_rB, P);
220  }
221 
222  // upper
223  {
224  float C = m_maxLength - m_currentLength;
225  float bias = b2Max(0.0f, C) * data.step.inv_dt;
226 
227  b2Vec2 vpA = vA + b2Cross(wA, m_rA);
228  b2Vec2 vpB = vB + b2Cross(wB, m_rB);
229  float Cdot = b2Dot(m_u, vpA - vpB);
230 
231  float impulse = -m_mass * (Cdot + bias);
232  float oldImpulse = m_upperImpulse;
233  m_upperImpulse = b2Max(0.0f, m_upperImpulse + impulse);
234  impulse = m_upperImpulse - oldImpulse;
235  b2Vec2 P = -impulse * m_u;
236 
237  vA -= m_invMassA * P;
238  wA -= m_invIA * b2Cross(m_rA, P);
239  vB += m_invMassB * P;
240  wB += m_invIB * b2Cross(m_rB, P);
241  }
242  }
243  else
244  {
245  // Equal limits
246 
247  // Cdot = dot(u, v + cross(w, r))
248  b2Vec2 vpA = vA + b2Cross(wA, m_rA);
249  b2Vec2 vpB = vB + b2Cross(wB, m_rB);
250  float Cdot = b2Dot(m_u, vpB - vpA);
251 
252  float impulse = -m_mass * Cdot;
253  m_impulse += impulse;
254 
255  b2Vec2 P = impulse * m_u;
256  vA -= m_invMassA * P;
257  wA -= m_invIA * b2Cross(m_rA, P);
258  vB += m_invMassB * P;
259  wB += m_invIB * b2Cross(m_rB, P);
260  }
261 
262  data.velocities[m_indexA].v = vA;
263  data.velocities[m_indexA].w = wA;
264  data.velocities[m_indexB].v = vB;
265  data.velocities[m_indexB].w = wB;
266 }
267 
269 {
270  b2Vec2 cA = data.positions[m_indexA].c;
271  float aA = data.positions[m_indexA].a;
272  b2Vec2 cB = data.positions[m_indexB].c;
273  float aB = data.positions[m_indexB].a;
274 
275  b2Rot qA(aA), qB(aB);
276 
279  b2Vec2 u = cB + rB - cA - rA;
280 
281  float length = u.Normalize();
282  float C;
283  if (m_minLength == m_maxLength)
284  {
285  C = length - m_minLength;
286  }
287  else if (length < m_minLength)
288  {
289  C = length - m_minLength;
290  }
291  else if (m_maxLength < length)
292  {
293  C = length - m_maxLength;
294  }
295  else
296  {
297  return true;
298  }
299 
300  float impulse = -m_mass * C;
301  b2Vec2 P = impulse * u;
302 
303  cA -= m_invMassA * P;
304  aA -= m_invIA * b2Cross(rA, P);
305  cB += m_invMassB * P;
306  aB += m_invIB * b2Cross(rB, P);
307 
308  data.positions[m_indexA].c = cA;
309  data.positions[m_indexA].a = aA;
310  data.positions[m_indexB].c = cB;
311  data.positions[m_indexB].a = aB;
312 
313  return b2Abs(C) < b2_linearSlop;
314 }
315 
317 {
319 }
320 
322 {
324 }
325 
327 {
328  b2Vec2 F = inv_dt * (m_impulse + m_lowerImpulse - m_upperImpulse) * m_u;
329  return F;
330 }
331 
332 float b2DistanceJoint::GetReactionTorque(float inv_dt) const
333 {
334  B2_NOT_USED(inv_dt);
335  return 0.0f;
336 }
337 
339 {
340  m_impulse = 0.0f;
341  m_length = b2Max(b2_linearSlop, length);
342  return m_length;
343 }
344 
345 float b2DistanceJoint::SetMinLength(float minLength)
346 {
347  m_lowerImpulse = 0.0f;
349  return m_minLength;
350 }
351 
352 float b2DistanceJoint::SetMaxLength(float maxLength)
353 {
354  m_upperImpulse = 0.0f;
355  m_maxLength = b2Max(maxLength, m_minLength);
356  return m_maxLength;
357 }
358 
360 {
363  b2Vec2 d = pB - pA;
364  float length = d.Length();
365  return length;
366 }
367 
369 {
370  int32 indexA = m_bodyA->m_islandIndex;
371  int32 indexB = m_bodyB->m_islandIndex;
372 
373  b2Dump(" b2DistanceJointDef jd;\n");
374  b2Dump(" jd.bodyA = bodies[%d];\n", indexA);
375  b2Dump(" jd.bodyB = bodies[%d];\n", indexB);
376  b2Dump(" jd.collideConnected = bool(%d);\n", m_collideConnected);
377  b2Dump(" jd.localAnchorA.Set(%.9g, %.9g);\n", m_localAnchorA.x, m_localAnchorA.y);
378  b2Dump(" jd.localAnchorB.Set(%.9g, %.9g);\n", m_localAnchorB.x, m_localAnchorB.y);
379  b2Dump(" jd.length = %.9g;\n", m_length);
380  b2Dump(" jd.minLength = %.9g;\n", m_minLength);
381  b2Dump(" jd.maxLength = %.9g;\n", m_maxLength);
382  b2Dump(" jd.stiffness = %.9g;\n", m_stiffness);
383  b2Dump(" jd.damping = %.9g;\n", m_damping);
384  b2Dump(" joints[%d] = m_world->CreateJoint(&jd);\n", m_index);
385 }
386 
387 void b2DistanceJoint::Draw(b2Draw* draw) const
388 {
389  const b2Transform& xfA = m_bodyA->GetTransform();
390  const b2Transform& xfB = m_bodyB->GetTransform();
391  b2Vec2 pA = b2Mul(xfA, m_localAnchorA);
392  b2Vec2 pB = b2Mul(xfB, m_localAnchorB);
393 
394  b2Vec2 axis = pB - pA;
395  float length = axis.Normalize();
396 
397  b2Color c1(0.7f, 0.7f, 0.7f);
398  b2Color c2(0.3f, 0.9f, 0.3f);
399  b2Color c3(0.9f, 0.3f, 0.3f);
400  b2Color c4(0.4f, 0.4f, 0.4f);
401 
402  draw->DrawSegment(pA, pB, c4);
403 
404  b2Vec2 pRest = pA + m_length * axis;
405  draw->DrawPoint(pRest, 8.0f, c1);
406 
407  if (m_minLength != m_maxLength)
408  {
410  {
411  b2Vec2 pMin = pA + m_minLength * axis;
412  draw->DrawPoint(pMin, 4.0f, c2);
413  }
414 
415  if (m_maxLength < FLT_MAX)
416  {
417  b2Vec2 pMax = pA + m_maxLength * axis;
418  draw->DrawPoint(pMax, 4.0f, c3);
419  }
420  }
421 }
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.
void Draw(b2Draw *draw) const override
Debug draw this joint.
b2Velocity * velocities
Definition: b2_time_step.h:71
float SetMinLength(float minLength)
int32 m_islandIndex
Definition: b2_body.h:439
float SetMaxLength(float maxLength)
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
Definition: b2_math.h:422
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
Definition: b2_math.h:395
f
b2TimeStep step
Definition: b2_time_step.h:69
float GetReactionTorque(float inv_dt) const override
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
float minLength
Minimum length. Clamped to a stable minimum value.
b2Vec2 c
Definition: b2_time_step.h:55
virtual void DrawPoint(const b2Vec2 &p, float size, const b2Color &color)=0
Draw a point.
bool m_collideConnected
Definition: b2_joint.h:188
GLenum GLuint GLenum GLsizei length
Definition: gl.h:1033
#define b2_linearSlop
Definition: b2_common.h:65
float stiffness
The linear stiffness in N/m.
b2Vec2 GetReactionForce(float inv_dt) const override
Solver Data.
Definition: b2_time_step.h:67
int32 m_index
Definition: b2_joint.h:185
A 2D column vector.
Definition: b2_math.h:41
signed int int32
Definition: b2_types.h:28
float GetCurrentLength() const
Get the current length.
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 InitVelocityConstraints(const b2SolverData &data) 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
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchorA, const b2Vec2 &anchorB)
#define B2_NOT_USED(x)
Definition: b2_common.h:36
T b2Max(T a, T b)
Definition: b2_math.h:637
void Set(float x_, float y_)
Set this vector to some specified coordinates.
Definition: b2_math.h:53
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
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
b2Vec2 localAnchorA
The local anchor point relative to bodyA&#39;s origin.
b2Body * m_bodyA
Definition: b2_joint.h:182
b2Vec2 localAnchorB
The local anchor point relative to bodyB&#39;s origin.
bool SolvePositionConstraints(const b2SolverData &data) override
T b2Clamp(T a, T low, T high)
Definition: b2_math.h:648
float length
The rest length of this joint. Clamped to a stable minimum value.
void SolveVelocityConstraints(const b2SolverData &data) override
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 maxLength
Maximum length. Must be greater than or equal to the minimum length.
float Normalize()
Convert this vector into a unit vector. Returns the length.
Definition: b2_math.h:102
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
Definition: b2_body.h:561
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
T b2Abs(T a)
Definition: b2_math.h:610
float SetLength(float length)
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
float damping
The linear damping in N*s/m.
b2Body * bodyB
The second attached body.
Definition: b2_joint.h:92
b2Body * m_bodyB
Definition: b2_joint.h:183
b2DistanceJoint(const b2DistanceJointDef *data)
b2Sweep m_sweep
Definition: b2_body.h:442
void Dump() override
Dump joint to dmLog.


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