b2_weld_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_time_step.h"
25 #include "box2d/b2_weld_joint.h"
26 
27 // Point-to-point constraint
28 // C = p2 - p1
29 // Cdot = v2 - v1
30 // = v2 + cross(w2, r2) - v1 - cross(w1, r1)
31 // J = [-I -r1_skew I r2_skew ]
32 // Identity used:
33 // w k % (rx i + ry j) = w * (-ry i + rx j)
34 
35 // Angle constraint
36 // C = angle2 - angle1 - referenceAngle
37 // Cdot = w2 - w1
38 // J = [0 0 -1 0 0 1]
39 // K = invI1 + invI2
40 
41 void b2WeldJointDef::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  m_stiffness = def->stiffness;
57  m_damping = def->damping;
58 
60 }
61 
63 {
72 
73  float aA = data.positions[m_indexA].a;
74  b2Vec2 vA = data.velocities[m_indexA].v;
75  float wA = data.velocities[m_indexA].w;
76 
77  float aB = data.positions[m_indexB].a;
78  b2Vec2 vB = data.velocities[m_indexB].v;
79  float wB = data.velocities[m_indexB].w;
80 
81  b2Rot qA(aA), qB(aB);
82 
85 
86  // J = [-I -r1_skew I r2_skew]
87  // [ 0 -1 0 1]
88  // r_skew = [-ry; rx]
89 
90  // Matlab
91  // K = [ mA+r1y^2*iA+mB+r2y^2*iB, -r1y*iA*r1x-r2y*iB*r2x, -r1y*iA-r2y*iB]
92  // [ -r1y*iA*r1x-r2y*iB*r2x, mA+r1x^2*iA+mB+r2x^2*iB, r1x*iA+r2x*iB]
93  // [ -r1y*iA-r2y*iB, r1x*iA+r2x*iB, iA+iB]
94 
95  float mA = m_invMassA, mB = m_invMassB;
96  float iA = m_invIA, iB = m_invIB;
97 
98  b2Mat33 K;
99  K.ex.x = mA + mB + m_rA.y * m_rA.y * iA + m_rB.y * m_rB.y * iB;
100  K.ey.x = -m_rA.y * m_rA.x * iA - m_rB.y * m_rB.x * iB;
101  K.ez.x = -m_rA.y * iA - m_rB.y * iB;
102  K.ex.y = K.ey.x;
103  K.ey.y = mA + mB + m_rA.x * m_rA.x * iA + m_rB.x * m_rB.x * iB;
104  K.ez.y = m_rA.x * iA + m_rB.x * iB;
105  K.ex.z = K.ez.x;
106  K.ey.z = K.ez.y;
107  K.ez.z = iA + iB;
108 
109  if (m_stiffness > 0.0f)
110  {
111  K.GetInverse22(&m_mass);
112 
113  float invM = iA + iB;
114 
115  float C = aB - aA - m_referenceAngle;
116 
117  // Damping coefficient
118  float d = m_damping;
119 
120  // Spring stiffness
121  float k = m_stiffness;
122 
123  // magic formulas
124  float h = data.step.dt;
125  m_gamma = h * (d + h * k);
126  m_gamma = m_gamma != 0.0f ? 1.0f / m_gamma : 0.0f;
127  m_bias = C * h * k * m_gamma;
128 
129  invM += m_gamma;
130  m_mass.ez.z = invM != 0.0f ? 1.0f / invM : 0.0f;
131  }
132  else if (K.ez.z == 0.0f)
133  {
134  K.GetInverse22(&m_mass);
135  m_gamma = 0.0f;
136  m_bias = 0.0f;
137  }
138  else
139  {
141  m_gamma = 0.0f;
142  m_bias = 0.0f;
143  }
144 
145  if (data.step.warmStarting)
146  {
147  // Scale impulses to support a variable time step.
148  m_impulse *= data.step.dtRatio;
149 
151 
152  vA -= mA * P;
153  wA -= iA * (b2Cross(m_rA, P) + m_impulse.z);
154 
155  vB += mB * P;
156  wB += iB * (b2Cross(m_rB, P) + m_impulse.z);
157  }
158  else
159  {
160  m_impulse.SetZero();
161  }
162 
163  data.velocities[m_indexA].v = vA;
164  data.velocities[m_indexA].w = wA;
165  data.velocities[m_indexB].v = vB;
166  data.velocities[m_indexB].w = wB;
167 }
168 
170 {
171  b2Vec2 vA = data.velocities[m_indexA].v;
172  float wA = data.velocities[m_indexA].w;
173  b2Vec2 vB = data.velocities[m_indexB].v;
174  float wB = data.velocities[m_indexB].w;
175 
176  float mA = m_invMassA, mB = m_invMassB;
177  float iA = m_invIA, iB = m_invIB;
178 
179  if (m_stiffness > 0.0f)
180  {
181  float Cdot2 = wB - wA;
182 
183  float impulse2 = -m_mass.ez.z * (Cdot2 + m_bias + m_gamma * m_impulse.z);
184  m_impulse.z += impulse2;
185 
186  wA -= iA * impulse2;
187  wB += iB * impulse2;
188 
189  b2Vec2 Cdot1 = vB + b2Cross(wB, m_rB) - vA - b2Cross(wA, m_rA);
190 
191  b2Vec2 impulse1 = -b2Mul22(m_mass, Cdot1);
192  m_impulse.x += impulse1.x;
193  m_impulse.y += impulse1.y;
194 
195  b2Vec2 P = impulse1;
196 
197  vA -= mA * P;
198  wA -= iA * b2Cross(m_rA, P);
199 
200  vB += mB * P;
201  wB += iB * b2Cross(m_rB, P);
202  }
203  else
204  {
205  b2Vec2 Cdot1 = vB + b2Cross(wB, m_rB) - vA - b2Cross(wA, m_rA);
206  float Cdot2 = wB - wA;
207  b2Vec3 Cdot(Cdot1.x, Cdot1.y, Cdot2);
208 
209  b2Vec3 impulse = -b2Mul(m_mass, Cdot);
210  m_impulse += impulse;
211 
212  b2Vec2 P(impulse.x, impulse.y);
213 
214  vA -= mA * P;
215  wA -= iA * (b2Cross(m_rA, P) + impulse.z);
216 
217  vB += mB * P;
218  wB += iB * (b2Cross(m_rB, P) + impulse.z);
219  }
220 
221  data.velocities[m_indexA].v = vA;
222  data.velocities[m_indexA].w = wA;
223  data.velocities[m_indexB].v = vB;
224  data.velocities[m_indexB].w = wB;
225 }
226 
228 {
229  b2Vec2 cA = data.positions[m_indexA].c;
230  float aA = data.positions[m_indexA].a;
231  b2Vec2 cB = data.positions[m_indexB].c;
232  float aB = data.positions[m_indexB].a;
233 
234  b2Rot qA(aA), qB(aB);
235 
236  float mA = m_invMassA, mB = m_invMassB;
237  float iA = m_invIA, iB = m_invIB;
238 
241 
242  float positionError, angularError;
243 
244  b2Mat33 K;
245  K.ex.x = mA + mB + rA.y * rA.y * iA + rB.y * rB.y * iB;
246  K.ey.x = -rA.y * rA.x * iA - rB.y * rB.x * iB;
247  K.ez.x = -rA.y * iA - rB.y * iB;
248  K.ex.y = K.ey.x;
249  K.ey.y = mA + mB + rA.x * rA.x * iA + rB.x * rB.x * iB;
250  K.ez.y = rA.x * iA + rB.x * iB;
251  K.ex.z = K.ez.x;
252  K.ey.z = K.ez.y;
253  K.ez.z = iA + iB;
254 
255  if (m_stiffness > 0.0f)
256  {
257  b2Vec2 C1 = cB + rB - cA - rA;
258 
259  positionError = C1.Length();
260  angularError = 0.0f;
261 
262  b2Vec2 P = -K.Solve22(C1);
263 
264  cA -= mA * P;
265  aA -= iA * b2Cross(rA, P);
266 
267  cB += mB * P;
268  aB += iB * b2Cross(rB, P);
269  }
270  else
271  {
272  b2Vec2 C1 = cB + rB - cA - rA;
273  float C2 = aB - aA - m_referenceAngle;
274 
275  positionError = C1.Length();
276  angularError = b2Abs(C2);
277 
278  b2Vec3 C(C1.x, C1.y, C2);
279 
280  b2Vec3 impulse;
281  if (K.ez.z > 0.0f)
282  {
283  impulse = -K.Solve33(C);
284  }
285  else
286  {
287  b2Vec2 impulse2 = -K.Solve22(C1);
288  impulse.Set(impulse2.x, impulse2.y, 0.0f);
289  }
290 
291  b2Vec2 P(impulse.x, impulse.y);
292 
293  cA -= mA * P;
294  aA -= iA * (b2Cross(rA, P) + impulse.z);
295 
296  cB += mB * P;
297  aB += iB * (b2Cross(rB, P) + impulse.z);
298  }
299 
300  data.positions[m_indexA].c = cA;
301  data.positions[m_indexA].a = aA;
302  data.positions[m_indexB].c = cB;
303  data.positions[m_indexB].a = aB;
304 
305  return positionError <= b2_linearSlop && angularError <= b2_angularSlop;
306 }
307 
309 {
311 }
312 
314 {
316 }
317 
319 {
321  return inv_dt * P;
322 }
323 
324 float b2WeldJoint::GetReactionTorque(float inv_dt) const
325 {
326  return inv_dt * m_impulse.z;
327 }
328 
330 {
331  int32 indexA = m_bodyA->m_islandIndex;
332  int32 indexB = m_bodyB->m_islandIndex;
333 
334  b2Dump(" b2WeldJointDef jd;\n");
335  b2Dump(" jd.bodyA = bodies[%d];\n", indexA);
336  b2Dump(" jd.bodyB = bodies[%d];\n", indexB);
337  b2Dump(" jd.collideConnected = bool(%d);\n", m_collideConnected);
338  b2Dump(" jd.localAnchorA.Set(%.9g, %.9g);\n", m_localAnchorA.x, m_localAnchorA.y);
339  b2Dump(" jd.localAnchorB.Set(%.9g, %.9g);\n", m_localAnchorB.x, m_localAnchorB.y);
340  b2Dump(" jd.referenceAngle = %.9g;\n", m_referenceAngle);
341  b2Dump(" jd.stiffness = %.9g;\n", m_stiffness);
342  b2Dump(" jd.damping = %.9g;\n", m_damping);
343  b2Dump(" joints[%d] = m_world->CreateJoint(&jd);\n", m_index);
344 }
d
b2Vec2 b2Mul22(const b2Mat33 &A, const b2Vec2 &v)
Multiply a matrix times a vector.
Definition: b2_math.h:528
float z
Definition: b2_math.h:167
b2Velocity * velocities
Definition: b2_time_step.h:71
int32 m_islandIndex
Definition: b2_body.h:439
b2Vec2 m_localAnchorA
float GetReactionTorque(float inv_dt) const override
Get the reaction torque on bodyB in N*m.
b2Vec3 ex
Definition: b2_math.h:283
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.
Definition: b2_weld_joint.h:54
f
float referenceAngle
The bodyB angle minus bodyA angle in the reference state (radians).
Definition: b2_weld_joint.h:57
b2TimeStep step
Definition: b2_time_step.h:69
float m_invMassB
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 m_invMassA
b2Vec2 c
Definition: b2_time_step.h:55
bool m_collideConnected
Definition: b2_joint.h:188
void SolveVelocityConstraints(const b2SolverData &data) override
void InitVelocityConstraints(const b2SolverData &data) override
#define b2_linearSlop
Definition: b2_common.h:65
b2Vec2 GetReactionForce(float inv_dt) const override
Get the reaction force on bodyB at the joint anchor in Newtons.
#define b2_angularSlop
Definition: b2_common.h:69
b2Vec3 ez
Definition: b2_math.h:283
Solver Data.
Definition: b2_time_step.h:67
b2Vec2 m_localCenterA
int32 m_index
Definition: b2_joint.h:185
A 2D column vector.
Definition: b2_math.h:41
void GetSymInverse33(b2Mat33 *M) const
Returns the zero matrix if singular.
Definition: b2_math.cpp:75
signed int int32
Definition: b2_types.h:28
float m_invI
Definition: b2_body.h:463
b2Vec2 localCenter
local center of mass position
Definition: b2_math.h:382
A 2D column vector with 3 elements.
Definition: b2_math.h:132
void SetZero()
Set this vector to all zeros.
Definition: b2_math.h:141
A rigid body. These are created via b2World::CreateBody.
Definition: b2_body.h:128
b2Vec3 ey
Definition: b2_math.h:283
b2Vec2 v
Definition: b2_time_step.h:62
b2Vec2 m_localCenterB
b2Vec2 localAnchorA
The local anchor point relative to bodyA&#39;s origin.
Definition: b2_weld_joint.h:51
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 m_stiffness
float damping
The rotational damping in N*m*s.
Definition: b2_weld_joint.h:64
b2Vec3 Solve33(const b2Vec3 &b) const
Definition: b2_math.cpp:29
b2Vec3 m_impulse
float GetAngle() const
Definition: b2_body.h:489
b2Body * m_bodyA
Definition: b2_joint.h:182
float y
Definition: b2_math.h:167
A 3-by-3 matrix. Stored in column-major order.
Definition: b2_math.h:245
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
void Dump() override
Dump to b2Log.
b2Mat33 m_mass
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
b2WeldJoint(const b2WeldJointDef *def)
b2Vec2 m_localAnchorB
void b2Dump(const char *string,...)
Definition: b2_settings.cpp:57
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
Definition: b2_body.h:561
float x
Definition: b2_math.h:167
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
b2Vec2 Solve22(const b2Vec2 &b) const
Definition: b2_math.cpp:45
T b2Abs(T a)
Definition: b2_math.h:610
bool warmStarting
Definition: b2_time_step.h:49
Rotation.
Definition: b2_math.h:287
float dtRatio
Definition: b2_time_step.h:46
void GetInverse22(b2Mat33 *M) const
Definition: b2_math.cpp:60
void Set(float x_, float y_, float z_)
Set this vector to some specified coordinates.
Definition: b2_math.h:144
b2Body * bodyA
The first attached body.
Definition: b2_joint.h:89
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchor)
bool SolvePositionConstraints(const b2SolverData &data) override
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
float m_referenceAngle


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