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