46         b2Vec2 dA = anchorA - groundA;
    48         b2Vec2 dB = anchorB - groundB;
   108                 m_uA *= 1.0f / lengthA;
   115         if (lengthB > 10.0
f * b2_linearSlop)
   117                 m_uB *= 1.0f / lengthB;
   197         b2Rot qA(aA), qB(aB);
   211                 uA *= 1.0f / lengthA;
   218         if (lengthB > 10.0
f * b2_linearSlop)
   220                 uB *= 1.0f / lengthB;
   246         b2Vec2 PA = -impulse * uA;
   330         b2Log(
"  b2PulleyJointDef jd;\n");
   331         b2Log(
"  jd.bodyA = bodies[%d];\n", indexA);
   332         b2Log(
"  jd.bodyB = bodies[%d];\n", indexB);
   341         b2Log(
"  joints[%d] = m_world->CreateJoint(&jd);\n", 
m_index);
 
float32 b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors. 
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
b2Vec2 GetReactionForce(float32 inv_dt) const 
Get the reaction force on bodyB at the joint anchor in Newtons. 
void b2Log(const char *string,...)
Logging function. 
void InitVelocityConstraints(const b2SolverData &data)
float32 GetLengthA() const 
Get the current length of the segment attached to bodyA. 
float32 lengthA
The a reference length for the segment attached to bodyA. 
b2Vec2 GetGroundAnchorB() const 
Get the second ground anchor. 
b2PulleyJoint(const b2PulleyJointDef *data)
b2Vec2 GetAnchorA() const 
Get the anchor point on bodyA in world coordinates. 
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin. 
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const 
float32 GetCurrentLengthB() const 
Get the current length of the segment attached to bodyB. 
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin. 
float32 GetReactionTorque(float32 inv_dt) const 
Get the reaction torque on bodyB in N*m. 
void ShiftOrigin(const b2Vec2 &newOrigin)
Implement b2Joint::ShiftOrigin. 
void SetZero()
Set this vector to all zeros. 
float32 ratio
The pulley ratio, used to simulate a block-and-tackle. 
float32 GetRatio() const 
Get the pulley ratio. 
b2Vec2 localCenter
local center of mass position 
float32 b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar. 
b2Vec2 groundAnchorB
The second ground anchor in world coordinates. This point never moves. 
A rigid body. These are created via b2World::CreateBody. 
void SolveVelocityConstraints(const b2SolverData &data)
GLint GLenum GLsizei GLint GLsizei const GLvoid * data
b2Vec2 groundAnchorA
The first ground anchor in world coordinates. This point never moves. 
bool SolvePositionConstraints(const b2SolverData &data)
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &groundAnchorA, const b2Vec2 &groundAnchorB, const b2Vec2 &anchorA, const b2Vec2 &anchorB, float32 ratio)
Initialize the bodies, anchors, lengths, max lengths, and ratio using the world anchors. 
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const 
float32 GetLengthB() const 
Get the current length of the segment attached to bodyB. 
b2Vec2 GetAnchorB() const 
Get the anchor point on bodyB in world coordinates. 
GLdouble GLdouble GLdouble r
void Dump()
Dump joint to dmLog. 
b2Body * bodyA
The first attached body. 
b2Vec2 GetGroundAnchorA() const 
Get the first ground anchor. 
float32 Length() const 
Get the length of this vector (the norm). 
b2Body * bodyB
The second attached body. 
float32 lengthB
The a reference length for the segment attached to bodyB. 
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f
float32 GetCurrentLengthA() const 
Get the current length of the segment attached to bodyA.