117 fixedRotation =
false;
121 fixedRotation =
true;
177 bool fixedRotation = (iA + iB == 0.0f);
198 float Cdot = wB - wA;
213 float Cdot = wA - wB;
252 b2Rot qA(aA), qB(aB);
254 float angularError = 0.0f;
255 float positionError = 0.0f;
283 aB += m_invIB * limitImpulse;
284 angularError =
b2Abs(C);
294 b2Vec2 C = cB + rB - cA - rA;
295 positionError = C.
Length();
301 K.
ex.
x = mA + mB + iA * rA.y * rA.y + iB * rB.
y * rB.
y;
302 K.
ex.
y = -iA * rA.x * rA.y - iB * rB.
x * rB.
y;
304 K.
ey.
y = mA + mB + iA * rA.x * rA.x + iB * rB.
x * rB.
x;
309 aA -= iA *
b2Cross(rA, impulse);
312 aB += iB *
b2Cross(rB, impulse);
445 b2Dump(
" b2RevoluteJointDef jd;\n");
446 b2Dump(
" jd.bodyA = bodies[%d];\n", indexA);
447 b2Dump(
" jd.bodyB = bodies[%d];\n", indexB);
458 b2Dump(
" joints[%d] = m_world->CreateJoint(&jd);\n",
m_index);
482 const float L = 0.5f;
const b2Transform & GetTransform() const
virtual void DrawSegment(const b2Vec2 &p1, const b2Vec2 &p2, const b2Color &color)=0
Draw a line segment.
virtual void DrawCircle(const b2Vec2 ¢er, float radius, const b2Color &color)=0
Draw a circle.
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin.
float lowerAngle
The lower angle for the joint limit (radians).
b2Vec2 Solve(const b2Vec2 &b) const
void SetMotorSpeed(float speed)
Set the motor speed in radians per second.
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
bool IsMotorEnabled() const
Is the joint motor enabled?
#define b2_maxAngularCorrection
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchor)
float Length() const
Get the length of this vector (the norm).
float GetMotorTorque(float inv_dt) const
void SetLimits(float lower, float upper)
Set the joint limits in radians.
virtual void DrawPoint(const b2Vec2 &p, float size, const b2Color &color)=0
Draw a point.
void SolveVelocityConstraints(const b2SolverData &data) override
void SetMaxMotorTorque(float torque)
Set the maximum motor torque, usually in N-m.
void SetZero()
Set this vector to all zeros.
void Draw(b2Draw *draw) const override
Debug draw this joint.
Color for debug drawing. Each value has the range [0,1].
b2Vec2 localCenter
local center of mass position
void EnableMotor(bool flag)
Enable/disable the joint motor.
float GetReactionTorque(float inv_dt) const override
A rigid body. These are created via b2World::CreateBody.
float GetJointSpeed() const
Get the current joint angle speed in radians per second.
float GetJointAngle() const
Get the current joint angle in radians.
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin.
float b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
float referenceAngle
The bodyB angle minus bodyA angle in the reference state (radians).
bool IsLimitEnabled() const
Is the joint limit enabled?
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
bool SolvePositionConstraints(const b2SolverData &data) override
bool enableMotor
A flag to enable the joint motor.
float GetUpperLimit() const
Get the upper joint limit in radians.
T b2Clamp(T a, T low, T high)
b2RevoluteJoint(const b2RevoluteJointDef *def)
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
b2Vec2 GetReactionForce(float inv_dt) const override
float motorSpeed
The desired motor speed. Usually in radians per second.
float upperAngle
The upper angle for the joint limit (radians).
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const
void b2Dump(const char *string,...)
void InitVelocityConstraints(const b2SolverData &data) override
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
A 2-by-2 matrix. Stored in column-major order.
bool enableLimit
A flag to enable joint limits.
void EnableLimit(bool flag)
Enable/disable the joint limit.
b2Body * bodyA
The first attached body.
void Dump() override
Dump to b2Log.
float GetLowerLimit() const
Get the lower joint limit in radians.
b2Body * bodyB
The second attached body.
void Set(float angle)
Set using an angle in radians.