23 #ifndef B2_WELD_JOINT_H 24 #define B2_WELD_JOINT_H 37 localAnchorA.Set(0.0
f, 0.0
f);
38 localAnchorB.Set(0.0
f, 0.0
f);
39 referenceAngle = 0.0f;
void SetDamping(float damping)
Set/get damping in N*m*s.
virtual void SolveVelocityConstraints(const b2SolverData &data)=0
void SetStiffness(float hz)
Set/get stiffness in N*m.
virtual b2Vec2 GetReactionForce(float inv_dt) const =0
Get the reaction force on bodyB at the joint anchor in Newtons.
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin.
float referenceAngle
The bodyB angle minus bodyA angle in the reference state (radians).
Joint definitions are used to construct joints.
virtual float GetReactionTorque(float inv_dt) const =0
Get the reaction torque on bodyB in N*m.
A 2D column vector with 3 elements.
A rigid body. These are created via b2World::CreateBody.
virtual b2Vec2 GetAnchorA() const =0
Get the anchor point on bodyA in world coordinates.
virtual void InitVelocityConstraints(const b2SolverData &data)=0
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin.
virtual bool SolvePositionConstraints(const b2SolverData &data)=0
float GetStiffness() const
float damping
The rotational damping in N*m*s.
const b2Vec2 & GetLocalAnchorB() const
The local anchor point relative to bodyB's origin.
IMGUI_API void Initialize(ImGuiContext *context)
const b2Vec2 & GetLocalAnchorA() const
The local anchor point relative to bodyA's origin.
float GetReferenceAngle() const
Get the reference angle.
virtual void Dump()
Dump this joint to the log file.
A 3-by-3 matrix. Stored in column-major order.
virtual b2Vec2 GetAnchorB() const =0
Get the anchor point on bodyB in world coordinates.