60 float coordinateA, coordinateB;
176 b2Rot qA(aA), qB(aB), qC(aC), qD(aD);
259 float impulse = -
m_mass * Cdot;
292 b2Rot qA(aA), qB(aB), qC(aC), qD(aD);
294 float linearError = 0.0f;
296 float coordinateA, coordinateB;
299 float JwA, JwB, JwC, JwD;
352 float impulse = 0.0f;
358 cA +=
m_mA * impulse * JvAC;
359 aA +=
m_iA * impulse * JwA;
360 cB +=
m_mB * impulse * JvBD;
361 aB +=
m_iB * impulse * JwB;
362 cC -=
m_mC * impulse * JvAC;
363 aC -=
m_iC * impulse * JwC;
364 cD -=
m_mD * impulse * JvBD;
365 aD -=
m_iD * impulse * JwD;
421 b2Dump(
" b2GearJointDef jd;\n");
422 b2Dump(
" jd.bodyA = bodies[%d];\n", indexA);
423 b2Dump(
" jd.bodyB = bodies[%d];\n", indexB);
425 b2Dump(
" jd.joint1 = joints[%d];\n", index1);
426 b2Dump(
" jd.joint2 = joints[%d];\n", index2);
428 b2Dump(
" joints[%d] = m_world->CreateJoint(&jd);\n",
m_index);
b2Joint * joint2
The second revolute/prismatic joint attached to the gear joint.
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
b2Body * GetBodyA()
Get the first body attached to this joint.
b2Vec2 GetReactionForce(float inv_dt) const override
Get the reaction force on bodyB at the joint anchor in Newtons.
b2JointType GetType() const
Get the type of the concrete joint.
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
void SetZero()
Set this vector to all zeros.
void SolveVelocityConstraints(const b2SolverData &data) override
void SetRatio(float ratio)
Set/Get the gear ratio.
b2GearJoint(const b2GearJointDef *data)
b2Body * GetBodyB()
Get the second body attached to this joint.
b2Vec2 localCenter
local center of mass position
bool SolvePositionConstraints(const b2SolverData &data) override
float b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
b2Joint * joint1
The first revolute/prismatic joint attached to the gear joint.
bool b2IsValid(float x)
This function is used to ensure that a floating point number is not a NaN or infinity.
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
b2Vec2 b2MulT(const b2Mat22 &A, const b2Vec2 &v)
void b2Dump(const char *string,...)
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
void InitVelocityConstraints(const b2SolverData &data) override
void Dump() override
Dump joint to dmLog.
float GetReactionTorque(float inv_dt) const override
Get the reaction torque on bodyB in N*m.