301 b2Dump(
" b2MotorJointDef jd;\n");
302 b2Dump(
" jd.bodyA = bodies[%d];\n", indexA);
303 b2Dump(
" jd.bodyB = bodies[%d];\n", indexB);
310 b2Dump(
" joints[%d] = m_world->CreateJoint(&jd);\n",
m_index);
void Dump() override
Dump to b2Log.
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
void SetAngularOffset(float angularOffset)
Set/get the target angular offset, in radians.
void SetMaxTorque(float torque)
Set the maximum friction torque in N*m.
b2Vec2 GetAnchorB() const override
Get the anchor point on bodyB in world coordinates.
void Initialize(b2Body *bodyA, b2Body *bodyB)
Initialize the bodies and offsets using the current transforms.
b2Vec2 linearOffset
Position of bodyB minus the position of bodyA, in bodyA's frame, in meters.
void InitVelocityConstraints(const b2SolverData &data) override
float angularOffset
The bodyB angle minus bodyA angle in radians.
void SetCorrectionFactor(float factor)
Set the position correction factor in the range [0,1].
float maxForce
The maximum motor force in N.
const b2Vec2 & GetPosition() const
void SetZero()
Set this vector to all zeros.
void SetMaxForce(float force)
Set the maximum friction force in N.
const b2Vec2 & GetLinearOffset() const
float GetCorrectionFactor() const
Get the position correction factor in the range [0,1].
b2Vec2 GetAnchorA() const override
Get the anchor point on bodyA in world coordinates.
b2Vec2 localCenter
local center of mass position
A rigid body. These are created via b2World::CreateBody.
b2Mat22 GetInverse() const
float GetAngularOffset() const
float LengthSquared() const
b2MotorJoint(const b2MotorJointDef *def)
void SetLinearOffset(const b2Vec2 &linearOffset)
Set/get the target linear offset, in frame A, in meters.
float maxTorque
The maximum motor torque in N-m.
float b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
b2Vec2 GetReactionForce(float inv_dt) const override
Get the reaction force on bodyB at the joint anchor in Newtons.
bool SolvePositionConstraints(const b2SolverData &data) override
bool b2IsValid(float x)
This function is used to ensure that a floating point number is not a NaN or infinity.
void SolveVelocityConstraints(const b2SolverData &data) override
T b2Clamp(T a, T low, T high)
float GetMaxTorque() const
Get the maximum friction torque in N*m.
float GetReactionTorque(float inv_dt) const override
Get the reaction torque on bodyB in N*m.
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const
void b2Dump(const char *string,...)
float GetMaxForce() const
Get the maximum friction force in N.
float Normalize()
Convert this vector into a unit vector. Returns the length.
A 2-by-2 matrix. Stored in column-major order.
b2Body * bodyA
The first attached body.
float correctionFactor
Position correction factor in the range [0,1].
b2Body * bodyB
The second attached body.