b2_pulley_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_pulley_joint.h"
25 #include "box2d/b2_time_step.h"
26 
27 // Pulley:
28 // length1 = norm(p1 - s1)
29 // length2 = norm(p2 - s2)
30 // C0 = (length1 + ratio * length2)_initial
31 // C = C0 - (length1 + ratio * length2)
32 // u1 = (p1 - s1) / norm(p1 - s1)
33 // u2 = (p2 - s2) / norm(p2 - s2)
34 // Cdot = -dot(u1, v1 + cross(w1, r1)) - ratio * dot(u2, v2 + cross(w2, r2))
35 // J = -[u1 cross(r1, u1) ratio * u2 ratio * cross(r2, u2)]
36 // K = J * invM * JT
37 // = invMass1 + invI1 * cross(r1, u1)^2 + ratio^2 * (invMass2 + invI2 * cross(r2, u2)^2)
38 
40  const b2Vec2& groundA, const b2Vec2& groundB,
41  const b2Vec2& anchorA, const b2Vec2& anchorB,
42  float r)
43 {
44  bodyA = bA;
45  bodyB = bB;
46  groundAnchorA = groundA;
47  groundAnchorB = groundB;
48  localAnchorA = bodyA->GetLocalPoint(anchorA);
49  localAnchorB = bodyB->GetLocalPoint(anchorB);
50  b2Vec2 dA = anchorA - groundA;
51  lengthA = dA.Length();
52  b2Vec2 dB = anchorB - groundB;
53  lengthB = dB.Length();
54  ratio = r;
56 }
57 
59 : b2Joint(def)
60 {
65 
66  m_lengthA = def->lengthA;
67  m_lengthB = def->lengthB;
68 
69  b2Assert(def->ratio != 0.0f);
70  m_ratio = def->ratio;
71 
72  m_constant = def->lengthA + m_ratio * def->lengthB;
73 
74  m_impulse = 0.0f;
75 }
76 
78 {
87 
88  b2Vec2 cA = data.positions[m_indexA].c;
89  float aA = data.positions[m_indexA].a;
90  b2Vec2 vA = data.velocities[m_indexA].v;
91  float wA = data.velocities[m_indexA].w;
92 
93  b2Vec2 cB = data.positions[m_indexB].c;
94  float aB = data.positions[m_indexB].a;
95  b2Vec2 vB = data.velocities[m_indexB].v;
96  float wB = data.velocities[m_indexB].w;
97 
98  b2Rot qA(aA), qB(aB);
99 
102 
103  // Get the pulley axes.
104  m_uA = cA + m_rA - m_groundAnchorA;
105  m_uB = cB + m_rB - m_groundAnchorB;
106 
107  float lengthA = m_uA.Length();
108  float lengthB = m_uB.Length();
109 
110  if (lengthA > 10.0f * b2_linearSlop)
111  {
112  m_uA *= 1.0f / lengthA;
113  }
114  else
115  {
116  m_uA.SetZero();
117  }
118 
119  if (lengthB > 10.0f * b2_linearSlop)
120  {
121  m_uB *= 1.0f / lengthB;
122  }
123  else
124  {
125  m_uB.SetZero();
126  }
127 
128  // Compute effective mass.
129  float ruA = b2Cross(m_rA, m_uA);
130  float ruB = b2Cross(m_rB, m_uB);
131 
132  float mA = m_invMassA + m_invIA * ruA * ruA;
133  float mB = m_invMassB + m_invIB * ruB * ruB;
134 
135  m_mass = mA + m_ratio * m_ratio * mB;
136 
137  if (m_mass > 0.0f)
138  {
139  m_mass = 1.0f / m_mass;
140  }
141 
142  if (data.step.warmStarting)
143  {
144  // Scale impulses to support variable time steps.
145  m_impulse *= data.step.dtRatio;
146 
147  // Warm starting.
148  b2Vec2 PA = -(m_impulse) * m_uA;
149  b2Vec2 PB = (-m_ratio * m_impulse) * m_uB;
150 
151  vA += m_invMassA * PA;
152  wA += m_invIA * b2Cross(m_rA, PA);
153  vB += m_invMassB * PB;
154  wB += m_invIB * b2Cross(m_rB, PB);
155  }
156  else
157  {
158  m_impulse = 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  b2Vec2 vpA = vA + b2Cross(wA, m_rA);
175  b2Vec2 vpB = vB + b2Cross(wB, m_rB);
176 
177  float Cdot = -b2Dot(m_uA, vpA) - m_ratio * b2Dot(m_uB, vpB);
178  float impulse = -m_mass * Cdot;
179  m_impulse += impulse;
180 
181  b2Vec2 PA = -impulse * m_uA;
182  b2Vec2 PB = -m_ratio * impulse * m_uB;
183  vA += m_invMassA * PA;
184  wA += m_invIA * b2Cross(m_rA, PA);
185  vB += m_invMassB * PB;
186  wB += m_invIB * b2Cross(m_rB, PB);
187 
188  data.velocities[m_indexA].v = vA;
189  data.velocities[m_indexA].w = wA;
190  data.velocities[m_indexB].v = vB;
191  data.velocities[m_indexB].w = wB;
192 }
193 
195 {
196  b2Vec2 cA = data.positions[m_indexA].c;
197  float aA = data.positions[m_indexA].a;
198  b2Vec2 cB = data.positions[m_indexB].c;
199  float aB = data.positions[m_indexB].a;
200 
201  b2Rot qA(aA), qB(aB);
202 
205 
206  // Get the pulley axes.
207  b2Vec2 uA = cA + rA - m_groundAnchorA;
208  b2Vec2 uB = cB + rB - m_groundAnchorB;
209 
210  float lengthA = uA.Length();
211  float lengthB = uB.Length();
212 
213  if (lengthA > 10.0f * b2_linearSlop)
214  {
215  uA *= 1.0f / lengthA;
216  }
217  else
218  {
219  uA.SetZero();
220  }
221 
222  if (lengthB > 10.0f * b2_linearSlop)
223  {
224  uB *= 1.0f / lengthB;
225  }
226  else
227  {
228  uB.SetZero();
229  }
230 
231  // Compute effective mass.
232  float ruA = b2Cross(rA, uA);
233  float ruB = b2Cross(rB, uB);
234 
235  float mA = m_invMassA + m_invIA * ruA * ruA;
236  float mB = m_invMassB + m_invIB * ruB * ruB;
237 
238  float mass = mA + m_ratio * m_ratio * mB;
239 
240  if (mass > 0.0f)
241  {
242  mass = 1.0f / mass;
243  }
244 
245  float C = m_constant - lengthA - m_ratio * lengthB;
246  float linearError = b2Abs(C);
247 
248  float impulse = -mass * C;
249 
250  b2Vec2 PA = -impulse * uA;
251  b2Vec2 PB = -m_ratio * impulse * uB;
252 
253  cA += m_invMassA * PA;
254  aA += m_invIA * b2Cross(rA, PA);
255  cB += m_invMassB * PB;
256  aB += m_invIB * b2Cross(rB, PB);
257 
258  data.positions[m_indexA].c = cA;
259  data.positions[m_indexA].a = aA;
260  data.positions[m_indexB].c = cB;
261  data.positions[m_indexB].a = aB;
262 
263  return linearError < b2_linearSlop;
264 }
265 
267 {
269 }
270 
272 {
274 }
275 
277 {
278  b2Vec2 P = m_impulse * m_uB;
279  return inv_dt * P;
280 }
281 
282 float b2PulleyJoint::GetReactionTorque(float inv_dt) const
283 {
284  B2_NOT_USED(inv_dt);
285  return 0.0f;
286 }
287 
289 {
290  return m_groundAnchorA;
291 }
292 
294 {
295  return m_groundAnchorB;
296 }
297 
299 {
300  return m_lengthA;
301 }
302 
304 {
305  return m_lengthB;
306 }
307 
309 {
310  return m_ratio;
311 }
312 
314 {
317  b2Vec2 d = p - s;
318  return d.Length();
319 }
320 
322 {
325  b2Vec2 d = p - s;
326  return d.Length();
327 }
328 
330 {
331  int32 indexA = m_bodyA->m_islandIndex;
332  int32 indexB = m_bodyB->m_islandIndex;
333 
334  b2Dump(" b2PulleyJointDef 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.groundAnchorA.Set(%.9g, %.9g);\n", m_groundAnchorA.x, m_groundAnchorA.y);
339  b2Dump(" jd.groundAnchorB.Set(%.9g, %.9g);\n", m_groundAnchorB.x, m_groundAnchorB.y);
340  b2Dump(" jd.localAnchorA.Set(%.9g, %.9g);\n", m_localAnchorA.x, m_localAnchorA.y);
341  b2Dump(" jd.localAnchorB.Set(%.9g, %.9g);\n", m_localAnchorB.x, m_localAnchorB.y);
342  b2Dump(" jd.lengthA = %.9g;\n", m_lengthA);
343  b2Dump(" jd.lengthB = %.9g;\n", m_lengthB);
344  b2Dump(" jd.ratio = %.9g;\n", m_ratio);
345  b2Dump(" joints[%d] = m_world->CreateJoint(&jd);\n", m_index);
346 }
347 
348 void b2PulleyJoint::ShiftOrigin(const b2Vec2& newOrigin)
349 {
350  m_groundAnchorA -= newOrigin;
351  m_groundAnchorB -= newOrigin;
352 }
b2Cross
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::m_index
int32 m_index
Definition: b2_joint.h:185
b2_epsilon
#define b2_epsilon
Definition: b2_common.h:40
b2PulleyJoint::m_groundAnchorA
b2Vec2 m_groundAnchorA
Definition: b2_pulley_joint.h:129
b2Vec2::y
float y
Definition: b2_math.h:128
B2_NOT_USED
#define B2_NOT_USED(x)
Definition: b2_common.h:36
b2PulleyJointDef::ratio
float ratio
The pulley ratio, used to simulate a block-and-tackle.
Definition: b2_pulley_joint.h:73
b2PulleyJointDef::lengthA
float lengthA
The a reference length for the segment attached to bodyA.
Definition: b2_pulley_joint.h:67
b2PulleyJointDef
Definition: b2_pulley_joint.h:33
b2PulleyJoint::ShiftOrigin
void ShiftOrigin(const b2Vec2 &newOrigin) override
Implement b2Joint::ShiftOrigin.
Definition: b2_pulley_joint.cpp:348
b2PulleyJoint::GetCurrentLengthB
float GetCurrentLengthB() const
Get the current length of the segment attached to bodyB.
Definition: b2_pulley_joint.cpp:321
b2Position::c
b2Vec2 c
Definition: b2_time_step.h:55
s
XmlRpcServer s
b2PulleyJoint::m_indexA
int32 m_indexA
Definition: b2_pulley_joint.h:142
b2PulleyJoint::m_invMassA
float m_invMassA
Definition: b2_pulley_joint.h:150
b2Sweep::localCenter
b2Vec2 localCenter
local center of mass position
Definition: b2_math.h:382
b2PulleyJoint::m_localCenterB
b2Vec2 m_localCenterB
Definition: b2_pulley_joint.h:149
b2SolverData
Solver Data.
Definition: b2_time_step.h:67
b2PulleyJoint::GetAnchorB
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
Definition: b2_pulley_joint.cpp:271
b2PulleyJoint::m_localAnchorB
b2Vec2 m_localAnchorB
Definition: b2_pulley_joint.h:136
b2PulleyJoint::m_uA
b2Vec2 m_uA
Definition: b2_pulley_joint.h:144
b2Body::m_invMass
float m_invMass
Definition: b2_body.h:460
b2PulleyJoint::m_mass
float m_mass
Definition: b2_pulley_joint.h:154
b2PulleyJoint::GetReactionForce
b2Vec2 GetReactionForce(float inv_dt) const override
Get the reaction force on bodyB at the joint anchor in Newtons.
Definition: b2_pulley_joint.cpp:276
b2PulleyJoint::GetLengthB
float GetLengthB() const
Get the current length of the segment attached to bodyB.
Definition: b2_pulley_joint.cpp:303
b2Body
A rigid body. These are created via b2World::CreateBody.
Definition: b2_body.h:128
b2PulleyJointDef::localAnchorB
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin.
Definition: b2_pulley_joint.h:64
b2Vec2::SetZero
void SetZero()
Set this vector to all zeros.
Definition: b2_math.h:50
b2Mul
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
Definition: b2_math.h:422
b2Dump
void b2Dump(const char *string,...)
Definition: b2_settings.cpp:57
b2Velocity::v
b2Vec2 v
Definition: b2_time_step.h:62
b2PulleyJoint::m_localAnchorA
b2Vec2 m_localAnchorA
Definition: b2_pulley_joint.h:135
b2Vec2
A 2D column vector.
Definition: b2_math.h:41
b2PulleyJoint::Dump
void Dump() override
Dump joint to dmLog.
Definition: b2_pulley_joint.cpp:329
f
f
b2PulleyJoint::b2PulleyJoint
b2PulleyJoint(const b2PulleyJointDef *data)
Definition: b2_pulley_joint.cpp:58
b2SolverData::positions
b2Position * positions
Definition: b2_time_step.h:70
b2PulleyJointDef::groundAnchorA
b2Vec2 groundAnchorA
The first ground anchor in world coordinates. This point never moves.
Definition: b2_pulley_joint.h:55
b2PulleyJointDef::localAnchorA
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin.
Definition: b2_pulley_joint.h:61
b2PulleyJoint::SolveVelocityConstraints
void SolveVelocityConstraints(const b2SolverData &data) override
Definition: b2_pulley_joint.cpp:167
b2_pulley_joint.h
b2PulleyJoint::m_lengthB
float m_lengthB
Definition: b2_pulley_joint.h:132
b2Joint
Definition: b2_joint.h:110
b2SolverData::step
b2TimeStep step
Definition: b2_time_step.h:69
b2PulleyJoint::m_lengthA
float m_lengthA
Definition: b2_pulley_joint.h:131
b2PulleyJoint::m_ratio
float m_ratio
Definition: b2_pulley_joint.h:138
b2PulleyJoint::GetReactionTorque
float GetReactionTorque(float inv_dt) const override
Get the reaction torque on bodyB in N*m.
Definition: b2_pulley_joint.cpp:282
b2PulleyJoint::m_invIB
float m_invIB
Definition: b2_pulley_joint.h:153
b2PulleyJoint::SolvePositionConstraints
bool SolvePositionConstraints(const b2SolverData &data) override
Definition: b2_pulley_joint.cpp:194
b2PulleyJoint::GetAnchorA
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
Definition: b2_pulley_joint.cpp:266
b2SolverData::velocities
b2Velocity * velocities
Definition: b2_time_step.h:71
b2Dot
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
Definition: b2_math.h:395
b2Joint::m_collideConnected
bool m_collideConnected
Definition: b2_joint.h:188
b2PulleyJointDef::groundAnchorB
b2Vec2 groundAnchorB
The second ground anchor in world coordinates. This point never moves.
Definition: b2_pulley_joint.h:58
b2PulleyJoint::GetGroundAnchorB
b2Vec2 GetGroundAnchorB() const
Get the second ground anchor.
Definition: b2_pulley_joint.cpp:293
d
d
b2PulleyJoint::m_rB
b2Vec2 m_rB
Definition: b2_pulley_joint.h:147
b2Body::GetLocalPoint
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const
Definition: b2_body.h:571
b2Vec2::x
float x
Definition: b2_math.h:128
b2PulleyJointDef::Initialize
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &groundAnchorA, const b2Vec2 &groundAnchorB, const b2Vec2 &anchorA, const b2Vec2 &anchorB, float ratio)
Initialize the bodies, anchors, lengths, max lengths, and ratio using the world anchors.
Definition: b2_pulley_joint.cpp:39
b2Body::m_islandIndex
int32 m_islandIndex
Definition: b2_body.h:439
b2PulleyJoint::m_impulse
float m_impulse
Definition: b2_pulley_joint.h:139
b2Velocity::w
float w
Definition: b2_time_step.h:63
b2PulleyJoint::m_indexB
int32 m_indexB
Definition: b2_pulley_joint.h:143
b2PulleyJoint::m_constant
float m_constant
Definition: b2_pulley_joint.h:137
b2PulleyJoint::m_groundAnchorB
b2Vec2 m_groundAnchorB
Definition: b2_pulley_joint.h:130
b2Joint::m_bodyA
b2Body * m_bodyA
Definition: b2_joint.h:182
b2PulleyJoint::GetRatio
float GetRatio() const
Get the pulley ratio.
Definition: b2_pulley_joint.cpp:308
b2Position::a
float a
Definition: b2_time_step.h:56
b2PulleyJoint::m_uB
b2Vec2 m_uB
Definition: b2_pulley_joint.h:145
b2TimeStep::warmStarting
bool warmStarting
Definition: b2_time_step.h:49
b2_time_step.h
int32
signed int int32
Definition: b2_types.h:28
b2PulleyJoint::GetGroundAnchorA
b2Vec2 GetGroundAnchorA() const
Get the first ground anchor.
Definition: b2_pulley_joint.cpp:288
b2PulleyJoint::InitVelocityConstraints
void InitVelocityConstraints(const b2SolverData &data) override
Definition: b2_pulley_joint.cpp:77
b2PulleyJointDef::lengthB
float lengthB
The a reference length for the segment attached to bodyB.
Definition: b2_pulley_joint.h:70
b2PulleyJoint::m_localCenterA
b2Vec2 m_localCenterA
Definition: b2_pulley_joint.h:148
b2Body::m_sweep
b2Sweep m_sweep
Definition: b2_body.h:442
b2PulleyJoint::m_invIA
float m_invIA
Definition: b2_pulley_joint.h:152
b2Rot
Rotation.
Definition: b2_math.h:287
b2Assert
#define b2Assert(A)
Definition: b2_common.h:37
b2Body::GetWorldPoint
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
Definition: b2_body.h:561
b2PulleyJoint::m_rA
b2Vec2 m_rA
Definition: b2_pulley_joint.h:146
b2Joint::m_bodyB
b2Body * m_bodyB
Definition: b2_joint.h:183
b2_linearSlop
#define b2_linearSlop
Definition: b2_common.h:65
b2PulleyJoint::m_invMassB
float m_invMassB
Definition: b2_pulley_joint.h:151
b2Vec2::Length
float Length() const
Get the length of this vector (the norm).
Definition: b2_math.h:89
b2Body::m_invI
float m_invI
Definition: b2_body.h:463
b2JointDef::bodyA
b2Body * bodyA
The first attached body.
Definition: b2_joint.h:89
b2Abs
T b2Abs(T a)
Definition: b2_math.h:610
b2PulleyJoint::GetLengthA
float GetLengthA() const
Get the current length of the segment attached to bodyA.
Definition: b2_pulley_joint.cpp:298
b2PulleyJoint::GetCurrentLengthA
float GetCurrentLengthA() const
Get the current length of the segment attached to bodyA.
Definition: b2_pulley_joint.cpp:313
b2TimeStep::dtRatio
float dtRatio
Definition: b2_time_step.h:46
b2JointDef::bodyB
b2Body * bodyB
The second attached body.
Definition: b2_joint.h:92
b2_body.h


mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:07