135 b2Rot qA(aA), qB(aB);
140 b2Vec2 d = (cB - cA) + rB - rA;
247 float LA = impulse *
m_a1;
248 float LB = impulse *
m_a2;
268 float LA = impulse *
m_a1;
269 float LB = impulse *
m_a2;
289 float LA = impulse *
m_a1;
290 float LB = impulse *
m_a2;
309 float LA = df.
x *
m_s1 + df.
y;
310 float LB = df.
x *
m_s2 + df.
y;
339 b2Rot qA(aA), qB(aB);
350 float a1 =
b2Cross(d + rA, axis);
354 float s1 =
b2Cross(d + rA, perp);
362 float linearError =
b2Abs(C1.
x);
363 float angularError =
b2Abs(C1.
y);
369 float translation =
b2Dot(axis, d);
373 linearError =
b2Max(linearError,
b2Abs(translation));
392 float k11 = mA + mB + iA * s1 * s1 + iB * s2 * s2;
393 float k12 = iA * s1 + iB * s2;
394 float k13 = iA * s1 * a1 + iB * s2 * a2;
401 float k23 = iA * a1 + iB * a2;
402 float k33 = mA + mB + iA * a1 * a1 + iB * a2 * a2;
405 K.
ex.
Set(k11, k12, k13);
406 K.
ey.
Set(k12, k22, k23);
407 K.
ez.
Set(k13, k23, k33);
418 float k11 = mA + mB + iA * s1 * s1 + iB * s2 * s2;
419 float k12 = iA * s1 + iB * s2;
431 impulse.
x = impulse1.
x;
432 impulse.
y = impulse1.
y;
436 b2Vec2 P = impulse.
x * perp + impulse.
z * axis;
437 float LA = impulse.
x * s1 + impulse.
y + impulse.
z * a1;
438 float LB = impulse.
x * s2 + impulse.
y + impulse.
z * a2;
480 float translation =
b2Dot(d, axis);
593 b2Dump(
" b2PrismaticJointDef jd;\n");
594 b2Dump(
" jd.bodyA = bodies[%d];\n", indexA);
595 b2Dump(
" jd.bodyB = bodies[%d];\n", indexB);
607 b2Dump(
" joints[%d] = m_world->CreateJoint(&jd);\n",
m_index);
633 draw->
DrawSegment(lower - 0.5
f * perp, lower + 0.5
f * perp, c2);
634 draw->
DrawSegment(upper - 0.5
f * perp, upper + 0.5
f * perp, c3);
const b2Transform & GetTransform() const
void Draw(b2Draw *draw) const override
Debug draw this joint.
virtual void DrawSegment(const b2Vec2 &p1, const b2Vec2 &p2, const b2Color &color)=0
Draw a line segment.
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
float GetLowerLimit() const
Get the lower joint limit, usually in meters.
b2Vec2 Solve(const b2Vec2 &b) const
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
b2Vec2 GetReactionForce(float inv_dt) const override
Get the reaction force on bodyB at the joint anchor in Newtons.
virtual void DrawPoint(const b2Vec2 &p, float size, const b2Color &color)=0
Draw a point.
b2Vec2 localAxisA
The local translation unit axis in bodyA.
void SetMotorSpeed(float speed)
Set the motor speed, usually in meters per second.
void SetZero()
Set this vector to all zeros.
float lowerTranslation
The lower translation limit, usually in meters.
b2Vec2 c
center world positions
Color for debug drawing. Each value has the range [0,1].
b2Vec2 localCenter
local center of mass position
float GetMotorForce(float inv_dt) const
Get the current motor force given the inverse time step, usually in N.
A 2D column vector with 3 elements.
A rigid body. These are created via b2World::CreateBody.
float maxMotorForce
The maximum motor torque, usually in N-m.
void SolveVelocityConstraints(const b2SolverData &data) override
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin.
float motorSpeed
The desired motor speed in radians per second.
b2Vec2 GetLocalVector(const b2Vec2 &worldVector) const
bool SolvePositionConstraints(const b2SolverData &data) override
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.
bool enableLimit
Enable/disable the joint limit.
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchor, const b2Vec2 &axis)
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
b2Vec2 GetWorldVector(const b2Vec2 &localVector) const
b2Vec3 Solve33(const b2Vec3 &b) const
b2PrismaticJoint(const b2PrismaticJointDef *def)
T b2Clamp(T a, T low, T high)
void EnableLimit(bool flag)
Enable/disable the joint limit.
A 3-by-3 matrix. Stored in column-major order.
float upperTranslation
The upper translation limit, usually in meters.
void InitVelocityConstraints(const b2SolverData &data) override
float GetUpperLimit() const
Get the upper joint limit, usually in meters.
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const
void b2Dump(const char *string,...)
bool enableMotor
Enable/disable the joint motor.
float Normalize()
Convert this vector into a unit vector. Returns the length.
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
float GetJointSpeed() const
Get the current joint translation speed, usually in meters per second.
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.
void SetLimits(float lower, float upper)
Set the joint limits, usually in meters.
void Set(float x_, float y_, float z_)
Set this vector to some specified coordinates.
void Dump() override
Dump to b2Log.
b2Body * bodyA
The first attached body.
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
bool IsMotorEnabled() const
Is the joint motor enabled?
void SetMaxMotorForce(float force)
Set the maximum motor force, usually in N.
float GetJointTranslation() const
Get the current joint translation, usually in meters.
float GetReactionTorque(float inv_dt) const override
Get the reaction torque on bodyB in N*m.
b2Body * bodyB
The second attached body.
bool IsLimitEnabled() const
Is the joint limit enabled?
float referenceAngle
The constrained angle between the bodies: bodyB_angle - bodyA_angle.