50 b2Vec2 dA = anchorA - groundA;
52 b2Vec2 dB = anchorB - groundB;
112 m_uA *= 1.0f / lengthA;
119 if (lengthB > 10.0
f * b2_linearSlop)
121 m_uB *= 1.0f / lengthB;
178 float impulse = -
m_mass * Cdot;
201 b2Rot qA(aA), qB(aB);
210 float lengthA = uA.
Length();
211 float lengthB = uB.
Length();
215 uA *= 1.0f / lengthA;
222 if (lengthB > 10.0
f * b2_linearSlop)
224 uB *= 1.0f / lengthB;
246 float linearError =
b2Abs(C);
248 float impulse = -mass * C;
250 b2Vec2 PA = -impulse * uA;
334 b2Dump(
" b2PulleyJointDef jd;\n");
335 b2Dump(
" jd.bodyA = bodies[%d];\n", indexA);
336 b2Dump(
" jd.bodyB = bodies[%d];\n", indexB);
345 b2Dump(
" joints[%d] = m_world->CreateJoint(&jd);\n",
m_index);
b2Vec2 GetReactionForce(float inv_dt) const override
Get the reaction force on bodyB at the joint anchor in Newtons.
void ShiftOrigin(const b2Vec2 &newOrigin) override
Implement b2Joint::ShiftOrigin.
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
b2Vec2 GetGroundAnchorA() const
Get the first ground anchor.
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
float ratio
The pulley ratio, used to simulate a block-and-tackle.
float Length() const
Get the length of this vector (the norm).
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
float lengthA
The a reference length for the segment attached to bodyA.
b2PulleyJoint(const b2PulleyJointDef *data)
float GetLengthA() const
Get the current length of the segment attached to bodyA.
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin.
void Dump() override
Dump joint to dmLog.
b2Vec2 GetGroundAnchorB() const
Get the second ground anchor.
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin.
void InitVelocityConstraints(const b2SolverData &data) override
void SetZero()
Set this vector to all zeros.
float GetCurrentLengthB() const
Get the current length of the segment attached to bodyB.
b2Vec2 localCenter
local center of mass position
b2Vec2 groundAnchorB
The second ground anchor in world coordinates. This point never moves.
A rigid body. These are created via b2World::CreateBody.
float b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
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.
b2Vec2 groundAnchorA
The first ground anchor in world coordinates. This point never moves.
void SolveVelocityConstraints(const b2SolverData &data) override
float GetRatio() const
Get the pulley ratio.
float GetReactionTorque(float inv_dt) const override
Get the reaction torque on bodyB in N*m.
float lengthB
The a reference length for the segment attached to bodyB.
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const
void b2Dump(const char *string,...)
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
float GetCurrentLengthA() const
Get the current length of the segment attached to bodyA.
b2Body * bodyA
The first attached body.
float GetLengthB() const
Get the current length of the segment attached to bodyB.
b2Body * bodyB
The second attached body.
bool SolvePositionConstraints(const b2SolverData &data) override