119 float32 k = mass * (omega * omega);
178 m_impulse += impulse;
180 if (m_impulse.LengthSquared() > maxImpulse * maxImpulse)
182 m_impulse *= maxImpulse / m_impulse.Length();
184 impulse = m_impulse - oldImpulse;
216 return inv_dt * 0.0f;
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
float32 dampingRatio
The damping ratio. 0 = no damping, 1 = critical damping.
b2Vec2 GetAnchorA() const
Implements b2Joint.
float32 GetDampingRatio() const
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
void SetZero()
Set this vector to all zeros.
float32 GetReactionTorque(float32 inv_dt) const
Implements b2Joint.
bool IsValid() const
Does this vector contain finite coordinates?
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.
b2Vec2 GetReactionForce(float32 inv_dt) const
Implements b2Joint.
bool b2IsValid(float32 x)
This function is used to ensure that a floating point number is not a NaN or infinity.
float32 frequencyHz
The response speed.
float32 GetMaxForce() const
void SetMaxForce(float32 force)
Set/get the maximum force in Newtons.
GLint GLenum GLsizei GLint GLsizei const GLvoid * data
b2Vec2 b2MulT(const b2Mat22 &A, const b2Vec2 &v)
const b2Vec2 & GetTarget() const
void SetFrequency(float32 hz)
Set/get the frequency in Hertz.
bool SolvePositionConstraints(const b2SolverData &data)
void SolveVelocityConstraints(const b2SolverData &data)
b2Vec2 GetAnchorB() const
Implements b2Joint.
A 2-by-2 matrix. Stored in column-major order.
float32 GetFrequency() const
void ShiftOrigin(const b2Vec2 &newOrigin)
Implement b2Joint::ShiftOrigin.
void InitVelocityConstraints(const b2SolverData &data)
b2MouseJoint(const b2MouseJointDef *def)
void SetDampingRatio(float32 ratio)
Set/get the damping ratio (dimensionless).
const b2Transform & GetTransform() const
void SetTarget(const b2Vec2 &target)
Use this to update the target point.
b2Mat22 GetInverse() const
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f