121 m_mass = invMass != 0.0f ? 1.0f / invMass : 0.0f;
141 m_softMass = invMass != 0.0f ? 1.0f / invMass : 0.0f;
210 float impulse = -
m_mass * (Cdot + bias);
231 float impulse = -
m_mass * (Cdot + bias);
252 float impulse = -
m_mass * Cdot;
275 b2Rot qA(aA), qB(aB);
279 b2Vec2 u = cB + rB - cA - rA;
300 float impulse = -
m_mass * C;
373 b2Dump(
" b2DistanceJointDef jd;\n");
374 b2Dump(
" jd.bodyA = bodies[%d];\n", indexA);
375 b2Dump(
" jd.bodyB = bodies[%d];\n", indexB);
384 b2Dump(
" joints[%d] = m_world->CreateJoint(&jd);\n",
m_index);
const b2Transform & GetTransform() const
virtual void DrawSegment(const b2Vec2 &p1, const b2Vec2 &p2, const b2Color &color)=0
Draw a line segment.
void Draw(b2Draw *draw) const override
Debug draw this joint.
float SetMinLength(float minLength)
float SetMaxLength(float maxLength)
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
float GetReactionTorque(float inv_dt) const override
float Length() const
Get the length of this vector (the norm).
float minLength
Minimum length. Clamped to a stable minimum value.
virtual void DrawPoint(const b2Vec2 &p, float size, const b2Color &color)=0
Draw a point.
GLenum GLuint GLenum GLsizei length
float stiffness
The linear stiffness in N/m.
b2Vec2 GetReactionForce(float inv_dt) const override
float GetCurrentLength() const
Get the current length.
Color for debug drawing. Each value has the range [0,1].
b2Vec2 localCenter
local center of mass position
void InitVelocityConstraints(const b2SolverData &data) override
A rigid body. These are created via b2World::CreateBody.
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchorA, const b2Vec2 &anchorB)
void Set(float x_, float y_)
Set this vector to some specified coordinates.
float b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin.
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin.
bool SolvePositionConstraints(const b2SolverData &data) override
T b2Clamp(T a, T low, T high)
float length
The rest length of this joint. Clamped to a stable minimum value.
void SolveVelocityConstraints(const b2SolverData &data) override
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const
void b2Dump(const char *string,...)
float maxLength
Maximum length. Must be greater than or equal to the minimum length.
float Normalize()
Convert this vector into a unit vector. Returns the length.
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
float SetLength(float length)
b2Body * bodyA
The first attached body.
float damping
The linear damping in N*s/m.
b2Body * bodyB
The second attached body.
b2DistanceJoint(const b2DistanceJointDef *data)
void Dump() override
Dump joint to dmLog.