110                 float32 m = invM > 0.0f ? 1.0f / invM : 0.0f;
   126                 m_gamma = m_gamma != 0.0f ? 1.0f / m_gamma : 0.0f;
   130                 m_mass.
ez.
z = invM != 0.0f ? 1.0f / invM : 0.0f;
   132         else if (K.
ez.
z == 0.0f)
   207                 b2Vec3 Cdot(Cdot1.
x, Cdot1.
y, Cdot2);
   234         b2Rot qA(aA), qB(aB);
   242         float32 positionError, angularError;
   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;
   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;
   257                 b2Vec2 C1 =  cB + rB - cA - rA;
   259                 positionError = C1.
Length();
   272                 b2Vec2 C1 =  cB + rB - cA - rA;
   275                 positionError = C1.
Length();
   276                 angularError = 
b2Abs(C2);
   288                         impulse.
Set(impulse2.
x, impulse2.
y, 0.0f);
   294                 aA -= iA * (
b2Cross(rA, P) + impulse.
z);
   297                 aB += iB * (
b2Cross(rB, P) + impulse.
z);
   334         b2Log(
"  b2WeldJointDef jd;\n");
   335         b2Log(
"  jd.bodyA = bodies[%d];\n", indexA);
   336         b2Log(
"  jd.bodyB = bodies[%d];\n", indexB);
   343         b2Log(
"  joints[%d] = m_world->CreateJoint(&jd);\n", 
m_index);
 
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
void SolveVelocityConstraints(const b2SolverData &data)
float32 referenceAngle
The bodyB angle minus bodyA angle in the reference state (radians). 
void b2Log(const char *string,...)
Logging function. 
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin. 
void GetInverse22(b2Mat33 *M) const 
float32 dampingRatio
The damping ratio. 0 = no damping, 1 = critical damping. 
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const 
b2Vec2 b2Mul22(const b2Mat33 &A, const b2Vec2 &v)
Multiply a matrix times a vector. 
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. 
A 2D column vector with 3 elements. 
void SetZero()
Set this vector to all zeros. 
A rigid body. These are created via b2World::CreateBody. 
void Dump()
Dump to b2Log. 
b2Vec2 GetAnchorA() const 
Get the anchor point on bodyA in world coordinates. 
float32 GetReactionTorque(float32 inv_dt) const 
Get the reaction torque on bodyB in N*m. 
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin. 
void InitVelocityConstraints(const b2SolverData &data)
b2Vec2 GetReactionForce(float32 inv_dt) const 
Get the reaction force on bodyB at the joint anchor in Newtons. 
A 3-by-3 matrix. Stored in column-major order. 
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const 
b2Vec2 Solve22(const b2Vec2 &b) const 
b2WeldJoint(const b2WeldJointDef *def)
b2Vec3 Solve33(const b2Vec3 &b) const 
void GetSymInverse33(b2Mat33 *M) const 
Returns the zero matrix if singular. 
void Set(float32 x_, float32 y_, float32 z_)
Set this vector to some specified coordinates. 
bool SolvePositionConstraints(const b2SolverData &data)
b2Body * bodyA
The first attached body. 
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchor)
float32 Length() const 
Get the length of this vector (the norm). 
b2Body * bodyB
The second attached body. 
b2Vec2 GetAnchorB() const 
Get the anchor point on bodyB in world coordinates.