113 b2Rot qA(aA), qB(aB);
254 float LA = impulse *
m_sAx;
255 float LB = impulse *
m_sBx;
290 float LA = impulse *
m_sAx;
291 float LB = impulse *
m_sBx;
311 float LA = impulse *
m_sAx;
312 float LB = impulse *
m_sBx;
324 float impulse = -
m_mass * Cdot;
328 float LA = impulse *
m_sAy;
329 float LB = impulse *
m_sBy;
351 float linearError = 0.0f;
355 b2Rot qA(aA), qB(aB);
359 b2Vec2 d = (cB - cA) + rB - rA;
366 float translation =
b2Dot(ax, d);
384 float impulse = 0.0f;
387 impulse = -C / invMass;
391 float LA = impulse * sAx;
392 float LB = impulse * sBx;
399 linearError =
b2Abs(C);
405 b2Rot qA(aA), qB(aB);
409 b2Vec2 d = (cB - cA) + rB - rA;
413 float sAy =
b2Cross(d + rA, ay);
416 float C =
b2Dot(d, ay);
420 float impulse = 0.0f;
423 impulse = - C / invMass;
427 float LA = impulse * sAy;
428 float LB = impulse * sBy;
476 float translation =
b2Dot(d, axis);
623 b2Dump(
" b2WheelJointDef jd;\n");
624 b2Dump(
" jd.bodyA = bodies[%d];\n", indexA);
625 b2Dump(
" jd.bodyB = bodies[%d];\n", indexB);
635 b2Dump(
" joints[%d] = m_world->CreateJoint(&jd);\n",
m_index);
662 draw->
DrawSegment(lower - 0.5
f * perp, lower + 0.5
f * perp, c2);
663 draw->
DrawSegment(upper - 0.5
f * perp, upper + 0.5
f * perp, c3);
const b2Transform & GetTransform() const
virtual void DrawSegment(const b2Vec2 &p1, const b2Vec2 &p2, const b2Color &color)=0
Draw a line segment.
b2WheelJoint(const b2WheelJointDef *def)
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
void Draw(b2Draw *draw) const override
Debug draw this joint.
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
void SolveVelocityConstraints(const b2SolverData &data) override
float lowerTranslation
The lower translation limit, usually in meters.
virtual void DrawPoint(const b2Vec2 &p, float size, const b2Color &color)=0
Draw a point.
bool IsLimitEnabled() const
Is the joint limit enabled?
void SetLimits(float lower, float upper)
Set the joint translation limits, usually in meters.
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchor, const b2Vec2 &axis)
void SetZero()
Set this vector to all zeros.
void SetMaxMotorTorque(float torque)
Set/Get the maximum motor force, usually in N-m.
void SetDamping(float damping)
Access damping.
b2Vec2 c
center world positions
Color for debug drawing. Each value has the range [0,1].
b2Vec2 localCenter
local center of mass position
void SetMotorSpeed(float speed)
Set the motor speed, usually in radians per second.
A rigid body. These are created via b2World::CreateBody.
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin.
float maxMotorTorque
The maximum motor torque, usually in N-m.
float GetUpperLimit() const
Get the upper joint translation limit, usually in meters.
float GetMotorTorque(float inv_dt) const
Get the current motor torque given the inverse time step, usually in N-m.
float GetJointTranslation() const
Get the current joint translation, usually in meters.
void SetStiffness(float stiffness)
Access spring stiffness.
b2Vec2 localAxisA
The local translation axis in bodyA.
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
b2Vec2 GetLocalVector(const b2Vec2 &worldVector) const
float b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
bool enableMotor
Enable/disable the joint motor.
b2Vec2 GetWorldVector(const b2Vec2 &localVector) const
float GetJointAngle() const
Get the current joint angle in radians.
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
float GetReactionTorque(float inv_dt) const override
Get the reaction torque on bodyB in N*m.
T b2Clamp(T a, T low, T high)
bool enableLimit
Enable/disable the joint limit.
bool SolvePositionConstraints(const b2SolverData &data) override
float GetJointLinearSpeed() const
Get the current joint linear speed, usually in meters per second.
float GetJointAngularSpeed() const
Get the current joint angular speed in radians per second.
void Dump() override
Dump to b2Log.
bool IsMotorEnabled() const
Is the joint motor enabled?
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const
void b2Dump(const char *string,...)
float GetLowerLimit() const
Get the lower joint translation limit, usually in meters.
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin.
void EnableMotor(bool flag)
Enable/disable the joint motor.
void InitVelocityConstraints(const b2SolverData &data) override
float motorSpeed
The desired motor speed in radians per second.
b2Vec2 GetReactionForce(float inv_dt) const override
Get the reaction force on bodyB at the joint anchor in Newtons.
b2Body * bodyA
The first attached body.
void EnableLimit(bool flag)
Enable/disable the joint translation limit.
float damping
Suspension damping. Typically in units of N*s/m.
float stiffness
Suspension stiffness. Typically in units N/m.
b2Body * bodyB
The second attached body.
float GetStiffness() const
float upperTranslation
The upper translation limit, usually in meters.