b2_gear_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_gear_joint.h"
26 #include "box2d/b2_body.h"
27 #include "box2d/b2_time_step.h"
28 
29 // Gear Joint:
30 // C0 = (coordinate1 + ratio * coordinate2)_initial
31 // C = (coordinate1 + ratio * coordinate2) - C0 = 0
32 // J = [J1 ratio * J2]
33 // K = J * invM * JT
34 // = J1 * invM1 * J1T + ratio * ratio * J2 * invM2 * J2T
35 //
36 // Revolute:
37 // coordinate = rotation
38 // Cdot = angularVelocity
39 // J = [0 0 1]
40 // K = J * invM * JT = invI
41 //
42 // Prismatic:
43 // coordinate = dot(p - pg, ug)
44 // Cdot = dot(v + cross(w, r), ug)
45 // J = [ug cross(r, ug)]
46 // K = J * invM * JT = invMass + invI * cross(r, ug)^2
47 
49 : b2Joint(def)
50 {
51  m_joint1 = def->joint1;
52  m_joint2 = def->joint2;
53 
56 
59 
60  float coordinateA, coordinateB;
61 
62  // TODO_ERIN there might be some problem with the joint edges in b2Joint.
63 
66 
67  // Body B on joint1 must be dynamic
69 
70  // Get geometry of joint1
71  b2Transform xfA = m_bodyA->m_xf;
72  float aA = m_bodyA->m_sweep.a;
73  b2Transform xfC = m_bodyC->m_xf;
74  float aC = m_bodyC->m_sweep.a;
75 
76  if (m_typeA == e_revoluteJoint)
77  {
78  b2RevoluteJoint* revolute = (b2RevoluteJoint*)def->joint1;
79  m_localAnchorC = revolute->m_localAnchorA;
80  m_localAnchorA = revolute->m_localAnchorB;
83 
84  coordinateA = aA - aC - m_referenceAngleA;
85  }
86  else
87  {
88  b2PrismaticJoint* prismatic = (b2PrismaticJoint*)def->joint1;
89  m_localAnchorC = prismatic->m_localAnchorA;
90  m_localAnchorA = prismatic->m_localAnchorB;
92  m_localAxisC = prismatic->m_localXAxisA;
93 
95  b2Vec2 pA = b2MulT(xfC.q, b2Mul(xfA.q, m_localAnchorA) + (xfA.p - xfC.p));
96  coordinateA = b2Dot(pA - pC, m_localAxisC);
97  }
98 
101 
102  // Body B on joint2 must be dynamic
104 
105  // Get geometry of joint2
106  b2Transform xfB = m_bodyB->m_xf;
107  float aB = m_bodyB->m_sweep.a;
108  b2Transform xfD = m_bodyD->m_xf;
109  float aD = m_bodyD->m_sweep.a;
110 
111  if (m_typeB == e_revoluteJoint)
112  {
113  b2RevoluteJoint* revolute = (b2RevoluteJoint*)def->joint2;
114  m_localAnchorD = revolute->m_localAnchorA;
115  m_localAnchorB = revolute->m_localAnchorB;
118 
119  coordinateB = aB - aD - m_referenceAngleB;
120  }
121  else
122  {
123  b2PrismaticJoint* prismatic = (b2PrismaticJoint*)def->joint2;
124  m_localAnchorD = prismatic->m_localAnchorA;
125  m_localAnchorB = prismatic->m_localAnchorB;
126  m_referenceAngleB = prismatic->m_referenceAngle;
127  m_localAxisD = prismatic->m_localXAxisA;
128 
129  b2Vec2 pD = m_localAnchorD;
130  b2Vec2 pB = b2MulT(xfD.q, b2Mul(xfB.q, m_localAnchorB) + (xfB.p - xfD.p));
131  coordinateB = b2Dot(pB - pD, m_localAxisD);
132  }
133 
134  m_ratio = def->ratio;
135 
136  m_constant = coordinateA + m_ratio * coordinateB;
137 
138  m_impulse = 0.0f;
139 }
140 
142 {
155  m_iA = m_bodyA->m_invI;
156  m_iB = m_bodyB->m_invI;
157  m_iC = m_bodyC->m_invI;
158  m_iD = m_bodyD->m_invI;
159 
160  float aA = data.positions[m_indexA].a;
161  b2Vec2 vA = data.velocities[m_indexA].v;
162  float wA = data.velocities[m_indexA].w;
163 
164  float aB = data.positions[m_indexB].a;
165  b2Vec2 vB = data.velocities[m_indexB].v;
166  float wB = data.velocities[m_indexB].w;
167 
168  float aC = data.positions[m_indexC].a;
169  b2Vec2 vC = data.velocities[m_indexC].v;
170  float wC = data.velocities[m_indexC].w;
171 
172  float aD = data.positions[m_indexD].a;
173  b2Vec2 vD = data.velocities[m_indexD].v;
174  float wD = data.velocities[m_indexD].w;
175 
176  b2Rot qA(aA), qB(aB), qC(aC), qD(aD);
177 
178  m_mass = 0.0f;
179 
180  if (m_typeA == e_revoluteJoint)
181  {
182  m_JvAC.SetZero();
183  m_JwA = 1.0f;
184  m_JwC = 1.0f;
185  m_mass += m_iA + m_iC;
186  }
187  else
188  {
189  b2Vec2 u = b2Mul(qC, m_localAxisC);
190  b2Vec2 rC = b2Mul(qC, m_localAnchorC - m_lcC);
191  b2Vec2 rA = b2Mul(qA, m_localAnchorA - m_lcA);
192  m_JvAC = u;
193  m_JwC = b2Cross(rC, u);
194  m_JwA = b2Cross(rA, u);
195  m_mass += m_mC + m_mA + m_iC * m_JwC * m_JwC + m_iA * m_JwA * m_JwA;
196  }
197 
198  if (m_typeB == e_revoluteJoint)
199  {
200  m_JvBD.SetZero();
201  m_JwB = m_ratio;
202  m_JwD = m_ratio;
203  m_mass += m_ratio * m_ratio * (m_iB + m_iD);
204  }
205  else
206  {
207  b2Vec2 u = b2Mul(qD, m_localAxisD);
208  b2Vec2 rD = b2Mul(qD, m_localAnchorD - m_lcD);
209  b2Vec2 rB = b2Mul(qB, m_localAnchorB - m_lcB);
210  m_JvBD = m_ratio * u;
211  m_JwD = m_ratio * b2Cross(rD, u);
212  m_JwB = m_ratio * b2Cross(rB, u);
213  m_mass += m_ratio * m_ratio * (m_mD + m_mB) + m_iD * m_JwD * m_JwD + m_iB * m_JwB * m_JwB;
214  }
215 
216  // Compute effective mass.
217  m_mass = m_mass > 0.0f ? 1.0f / m_mass : 0.0f;
218 
219  if (data.step.warmStarting)
220  {
221  vA += (m_mA * m_impulse) * m_JvAC;
222  wA += m_iA * m_impulse * m_JwA;
223  vB += (m_mB * m_impulse) * m_JvBD;
224  wB += m_iB * m_impulse * m_JwB;
225  vC -= (m_mC * m_impulse) * m_JvAC;
226  wC -= m_iC * m_impulse * m_JwC;
227  vD -= (m_mD * m_impulse) * m_JvBD;
228  wD -= m_iD * m_impulse * m_JwD;
229  }
230  else
231  {
232  m_impulse = 0.0f;
233  }
234 
235  data.velocities[m_indexA].v = vA;
236  data.velocities[m_indexA].w = wA;
237  data.velocities[m_indexB].v = vB;
238  data.velocities[m_indexB].w = wB;
239  data.velocities[m_indexC].v = vC;
240  data.velocities[m_indexC].w = wC;
241  data.velocities[m_indexD].v = vD;
242  data.velocities[m_indexD].w = wD;
243 }
244 
246 {
247  b2Vec2 vA = data.velocities[m_indexA].v;
248  float wA = data.velocities[m_indexA].w;
249  b2Vec2 vB = data.velocities[m_indexB].v;
250  float wB = data.velocities[m_indexB].w;
251  b2Vec2 vC = data.velocities[m_indexC].v;
252  float wC = data.velocities[m_indexC].w;
253  b2Vec2 vD = data.velocities[m_indexD].v;
254  float wD = data.velocities[m_indexD].w;
255 
256  float Cdot = b2Dot(m_JvAC, vA - vC) + b2Dot(m_JvBD, vB - vD);
257  Cdot += (m_JwA * wA - m_JwC * wC) + (m_JwB * wB - m_JwD * wD);
258 
259  float impulse = -m_mass * Cdot;
260  m_impulse += impulse;
261 
262  vA += (m_mA * impulse) * m_JvAC;
263  wA += m_iA * impulse * m_JwA;
264  vB += (m_mB * impulse) * m_JvBD;
265  wB += m_iB * impulse * m_JwB;
266  vC -= (m_mC * impulse) * m_JvAC;
267  wC -= m_iC * impulse * m_JwC;
268  vD -= (m_mD * impulse) * m_JvBD;
269  wD -= m_iD * impulse * m_JwD;
270 
271  data.velocities[m_indexA].v = vA;
272  data.velocities[m_indexA].w = wA;
273  data.velocities[m_indexB].v = vB;
274  data.velocities[m_indexB].w = wB;
275  data.velocities[m_indexC].v = vC;
276  data.velocities[m_indexC].w = wC;
277  data.velocities[m_indexD].v = vD;
278  data.velocities[m_indexD].w = wD;
279 }
280 
282 {
283  b2Vec2 cA = data.positions[m_indexA].c;
284  float aA = data.positions[m_indexA].a;
285  b2Vec2 cB = data.positions[m_indexB].c;
286  float aB = data.positions[m_indexB].a;
287  b2Vec2 cC = data.positions[m_indexC].c;
288  float aC = data.positions[m_indexC].a;
289  b2Vec2 cD = data.positions[m_indexD].c;
290  float aD = data.positions[m_indexD].a;
291 
292  b2Rot qA(aA), qB(aB), qC(aC), qD(aD);
293 
294  float linearError = 0.0f;
295 
296  float coordinateA, coordinateB;
297 
298  b2Vec2 JvAC, JvBD;
299  float JwA, JwB, JwC, JwD;
300  float mass = 0.0f;
301 
302  if (m_typeA == e_revoluteJoint)
303  {
304  JvAC.SetZero();
305  JwA = 1.0f;
306  JwC = 1.0f;
307  mass += m_iA + m_iC;
308 
309  coordinateA = aA - aC - m_referenceAngleA;
310  }
311  else
312  {
313  b2Vec2 u = b2Mul(qC, m_localAxisC);
314  b2Vec2 rC = b2Mul(qC, m_localAnchorC - m_lcC);
315  b2Vec2 rA = b2Mul(qA, m_localAnchorA - m_lcA);
316  JvAC = u;
317  JwC = b2Cross(rC, u);
318  JwA = b2Cross(rA, u);
319  mass += m_mC + m_mA + m_iC * JwC * JwC + m_iA * JwA * JwA;
320 
321  b2Vec2 pC = m_localAnchorC - m_lcC;
322  b2Vec2 pA = b2MulT(qC, rA + (cA - cC));
323  coordinateA = b2Dot(pA - pC, m_localAxisC);
324  }
325 
326  if (m_typeB == e_revoluteJoint)
327  {
328  JvBD.SetZero();
329  JwB = m_ratio;
330  JwD = m_ratio;
331  mass += m_ratio * m_ratio * (m_iB + m_iD);
332 
333  coordinateB = aB - aD - m_referenceAngleB;
334  }
335  else
336  {
337  b2Vec2 u = b2Mul(qD, m_localAxisD);
338  b2Vec2 rD = b2Mul(qD, m_localAnchorD - m_lcD);
339  b2Vec2 rB = b2Mul(qB, m_localAnchorB - m_lcB);
340  JvBD = m_ratio * u;
341  JwD = m_ratio * b2Cross(rD, u);
342  JwB = m_ratio * b2Cross(rB, u);
343  mass += m_ratio * m_ratio * (m_mD + m_mB) + m_iD * JwD * JwD + m_iB * JwB * JwB;
344 
345  b2Vec2 pD = m_localAnchorD - m_lcD;
346  b2Vec2 pB = b2MulT(qD, rB + (cB - cD));
347  coordinateB = b2Dot(pB - pD, m_localAxisD);
348  }
349 
350  float C = (coordinateA + m_ratio * coordinateB) - m_constant;
351 
352  float impulse = 0.0f;
353  if (mass > 0.0f)
354  {
355  impulse = -C / mass;
356  }
357 
358  cA += m_mA * impulse * JvAC;
359  aA += m_iA * impulse * JwA;
360  cB += m_mB * impulse * JvBD;
361  aB += m_iB * impulse * JwB;
362  cC -= m_mC * impulse * JvAC;
363  aC -= m_iC * impulse * JwC;
364  cD -= m_mD * impulse * JvBD;
365  aD -= m_iD * impulse * JwD;
366 
367  data.positions[m_indexA].c = cA;
368  data.positions[m_indexA].a = aA;
369  data.positions[m_indexB].c = cB;
370  data.positions[m_indexB].a = aB;
371  data.positions[m_indexC].c = cC;
372  data.positions[m_indexC].a = aC;
373  data.positions[m_indexD].c = cD;
374  data.positions[m_indexD].a = aD;
375 
376  // TODO_ERIN not implemented
377  return linearError < b2_linearSlop;
378 }
379 
381 {
383 }
384 
386 {
388 }
389 
391 {
392  b2Vec2 P = m_impulse * m_JvAC;
393  return inv_dt * P;
394 }
395 
396 float b2GearJoint::GetReactionTorque(float inv_dt) const
397 {
398  float L = m_impulse * m_JwA;
399  return inv_dt * L;
400 }
401 
402 void b2GearJoint::SetRatio(float ratio)
403 {
404  b2Assert(b2IsValid(ratio));
405  m_ratio = ratio;
406 }
407 
409 {
410  return m_ratio;
411 }
412 
414 {
415  int32 indexA = m_bodyA->m_islandIndex;
416  int32 indexB = m_bodyB->m_islandIndex;
417 
418  int32 index1 = m_joint1->m_index;
419  int32 index2 = m_joint2->m_index;
420 
421  b2Dump(" b2GearJointDef jd;\n");
422  b2Dump(" jd.bodyA = bodies[%d];\n", indexA);
423  b2Dump(" jd.bodyB = bodies[%d];\n", indexB);
424  b2Dump(" jd.collideConnected = bool(%d);\n", m_collideConnected);
425  b2Dump(" jd.joint1 = joints[%d];\n", index1);
426  b2Dump(" jd.joint2 = joints[%d];\n", index2);
427  b2Dump(" jd.ratio = %.9g;\n", m_ratio);
428  b2Dump(" joints[%d] = m_world->CreateJoint(&jd);\n", m_index);
429 }
b2Vec2 m_localAxisD
b2Velocity * velocities
Definition: b2_time_step.h:71
int32 m_islandIndex
Definition: b2_body.h:439
b2Joint * joint2
The second revolute/prismatic joint attached to the gear joint.
Definition: b2_gear_joint.h:45
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
Definition: b2_math.h:422
b2Joint * m_joint2
Definition: b2_gear_joint.h:93
b2Vec2 p
Definition: b2_math.h:360
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
b2Body * GetBodyA()
Get the first body attached to this joint.
Definition: b2_joint.h:198
b2TimeStep step
Definition: b2_time_step.h:69
b2Vec2 GetReactionForce(float inv_dt) const override
Get the reaction force on bodyB at the joint anchor in Newtons.
b2JointType GetType() const
Get the type of the concrete joint.
Definition: b2_joint.h:193
b2Vec2 c
Definition: b2_time_step.h:55
b2Body * m_bodyD
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
bool m_collideConnected
Definition: b2_joint.h:188
#define b2_linearSlop
Definition: b2_common.h:65
b2JointType m_typeA
Definition: b2_gear_joint.h:95
Solver Data.
Definition: b2_time_step.h:67
void SetZero()
Set this vector to all zeros.
Definition: b2_math.h:50
void SolveVelocityConstraints(const b2SolverData &data) override
int32 m_index
Definition: b2_joint.h:185
A 2D column vector.
Definition: b2_math.h:41
void SetRatio(float ratio)
Set/Get the gear ratio.
b2GearJoint(const b2GearJointDef *data)
signed int int32
Definition: b2_types.h:28
b2Body * GetBodyB()
Get the second body attached to this joint.
Definition: b2_joint.h:203
float m_invI
Definition: b2_body.h:463
b2Vec2 localCenter
local center of mass position
Definition: b2_math.h:382
float GetRatio() const
b2Vec2 v
Definition: b2_time_step.h:62
b2Vec2 m_localAnchorB
b2Body * m_bodyC
bool SolvePositionConstraints(const b2SolverData &data) override
b2Joint * m_joint1
Definition: b2_gear_joint.h:92
b2Vec2 m_localAnchorC
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 * joint1
The first revolute/prismatic joint attached to the gear joint.
Definition: b2_gear_joint.h:42
float m_referenceAngleA
float m_constant
bool b2IsValid(float x)
This function is used to ensure that a floating point number is not a NaN or infinity.
Definition: b2_math.h:32
b2Body * m_bodyA
Definition: b2_joint.h:182
float m_referenceAngleB
float m_invMass
Definition: b2_body.h:460
b2Position * positions
Definition: b2_time_step.h:70
b2Vec2 m_localAnchorA
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
b2Vec2 b2MulT(const b2Mat22 &A, const b2Vec2 &v)
Definition: b2_math.h:429
void b2Dump(const char *string,...)
Definition: b2_settings.cpp:57
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
Definition: b2_body.h:561
float a
world angles
Definition: b2_math.h:384
b2Vec2 m_localAxisC
b2JointType m_typeB
Definition: b2_gear_joint.h:96
b2Transform m_xf
Definition: b2_body.h:441
bool warmStarting
Definition: b2_time_step.h:49
Rotation.
Definition: b2_math.h:287
void InitVelocityConstraints(const b2SolverData &data) override
b2Vec2 m_localAnchorD
b2BodyType m_type
Definition: b2_body.h:435
#define b2Assert(A)
Definition: b2_common.h:37
void Dump() override
Dump joint to dmLog.
b2Body * m_bodyB
Definition: b2_joint.h:183
b2Sweep m_sweep
Definition: b2_body.h:442
float GetReactionTorque(float inv_dt) const override
Get the reaction torque on bodyB in N*m.


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