147         b2Rot qA(aA), qB(aB);
   152         b2Vec2 d = (cB - cA) + rB - rA;
   306                 b2Vec3 Cdot(Cdot1.
x, Cdot1.
y, Cdot2);
   370         b2Rot qA(aA), qB(aB);
   405                         linearError = 
b2Max(linearError, 
b2Abs(translation));
   426                 float32 k11 = mA + mB + iA * s1 * s1 + iB * s2 * s2;
   427                 float32 k12 = iA * s1 + iB * s2;
   428                 float32 k13 = iA * s1 * a1 + iB * s2 * a2;
   435                 float32 k23 = iA * a1 + iB * a2;
   436                 float32 k33 = mA + mB + iA * a1 * a1 + iB * a2 * a2;
   439                 K.
ex.
Set(k11, k12, k13);
   440                 K.
ey.
Set(k12, k22, k23);
   441                 K.
ez.
Set(k13, k23, k33);
   452                 float32 k11 = mA + mB + iA * s1 * s1 + iB * s2 * s2;
   453                 float32 k12 = iA * s1 + iB * s2;
   465                 impulse.
x = impulse1.
x;
   466                 impulse.
y = impulse1.
y;
   470         b2Vec2 P = impulse.
x * perp + impulse.
z * axis;
   471         float32 LA = impulse.
x * s1 + impulse.
y + impulse.
z * a1;
   472         float32 LB = impulse.
x * s2 + impulse.
y + impulse.
z * a2;
   614         b2Log(
"  b2PrismaticJointDef jd;\n");
   615         b2Log(
"  jd.bodyA = bodies[%d];\n", indexA);
   616         b2Log(
"  jd.bodyB = bodies[%d];\n", indexB);
   628         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 SetMotorSpeed(float32 speed)
Set the motor speed, usually in meters per second. 
float32 referenceAngle
The constrained angle between the bodies: bodyB_angle - bodyA_angle. 
bool SolvePositionConstraints(const b2SolverData &data)
float32 GetReactionTorque(float32 inv_dt) const 
Get the reaction torque on bodyB in N*m. 
float32 upperTranslation
The upper translation limit, usually in meters. 
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const 
b2Vec2 localAxisA
The local translation unit axis in bodyA. 
float32 GetUpperLimit() const 
Get the upper joint limit, usually in meters. 
void SetZero()
Set this vector to all zeros. 
float32 GetLowerLimit() const 
Get the lower joint limit, usually in meters. 
b2Vec2 c
center world positions 
#define b2_maxLinearCorrection
float32 GetJointSpeed() const 
Get the current joint translation speed, usually in meters per second. 
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. 
void SolveVelocityConstraints(const b2SolverData &data)
A 2D column vector with 3 elements. 
void SetZero()
Set this vector to all zeros. 
A rigid body. These are created via b2World::CreateBody. 
float32 GetJointTranslation() const 
Get the current joint translation, usually in meters. 
void InitVelocityConstraints(const b2SolverData &data)
void SetLimits(float32 lower, float32 upper)
Set the joint limits, usually in meters. 
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin. 
b2Vec2 GetWorldVector(const b2Vec2 &localVector) const 
bool IsMotorEnabled() const 
Is the joint motor enabled? 
bool enableLimit
Enable/disable the joint limit. 
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchor, const b2Vec2 &axis)
GLint GLenum GLsizei GLint GLsizei const GLvoid * data
b2PrismaticJoint(const b2PrismaticJointDef *def)
b2Vec2 Solve(const b2Vec2 &b) const 
float32 m_upperTranslation
void EnableLimit(bool flag)
Enable/disable the joint limit. 
void Dump()
Dump to b2Log. 
A 3-by-3 matrix. Stored in column-major order. 
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const 
bool IsLimitEnabled() const 
Is the joint limit enabled? 
void SetMaxMotorForce(float32 force)
Set the maximum motor force, usually in N. 
b2Vec2 GetLocalVector(const b2Vec2 &worldVector) const 
b2Vec2 GetAnchorA() const 
Get the anchor point on bodyA in world coordinates. 
b2Vec2 Solve22(const b2Vec2 &b) const 
b2Vec3 Solve33(const b2Vec3 &b) const 
b2Vec2 GetAnchorB() const 
Get the anchor point on bodyB in world coordinates. 
T b2Clamp(T a, T low, T high)
float32 motorSpeed
The desired motor speed in radians per second. 
bool enableMotor
Enable/disable the joint motor. 
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin. 
A 2-by-2 matrix. Stored in column-major order. 
void EnableMotor(bool flag)
Enable/disable the joint motor. 
float32 m_angularVelocity
b2LimitState m_limitState
void Set(float32 x_, float32 y_, float32 z_)
Set this vector to some specified coordinates. 
GLdouble GLdouble GLdouble b
float32 m_lowerTranslation
b2Body * bodyA
The first attached body. 
float32 Normalize()
Convert this vector into a unit vector. Returns the length. 
void Set(float32 x_, float32 y_)
Set this vector to some specified coordinates. 
float32 GetMotorForce(float32 inv_dt) const 
Get the current motor force given the inverse time step, usually in N. 
float32 lowerTranslation
The lower translation limit, usually in meters. 
b2Body * bodyB
The second attached body. 
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f
float32 maxMotorForce
The maximum motor torque, usually in N-m.