23 #ifndef B2_WHEEL_JOINT_H 24 #define B2_WHEEL_JOINT_H 40 localAnchorA.SetZero();
41 localAnchorB.SetZero();
42 localAxisA.Set(1.0
f, 0.0
f);
44 lowerTranslation = 0.0f;
45 upperTranslation = 0.0f;
47 maxMotorTorque = 0.0f;
114 float GetJointTranslation()
const;
117 float GetJointLinearSpeed()
const;
120 float GetJointAngle()
const;
123 float GetJointAngularSpeed()
const;
126 bool IsLimitEnabled()
const;
129 void EnableLimit(
bool flag);
132 float GetLowerLimit()
const;
135 float GetUpperLimit()
const;
138 void SetLimits(
float lower,
float upper);
141 bool IsMotorEnabled()
const;
144 void EnableMotor(
bool flag);
147 void SetMotorSpeed(
float speed);
150 float GetMotorSpeed()
const;
153 void SetMaxMotorTorque(
float torque);
154 float GetMaxMotorTorque()
const;
157 float GetMotorTorque(
float inv_dt)
const;
160 void SetStiffness(
float stiffness);
161 float GetStiffness()
const;
164 void SetDamping(
float damping);
165 float GetDamping()
const;
168 void Dump()
override;
237 return m_maxMotorTorque;
virtual void SolveVelocityConstraints(const b2SolverData &data)=0
virtual b2Vec2 GetReactionForce(float inv_dt) const =0
Get the reaction force on bodyB at the joint anchor in Newtons.
Joint definitions are used to construct joints.
float lowerTranslation
The lower translation limit, usually in meters.
const b2Vec2 & GetLocalAnchorB() const
The local anchor point relative to bodyB's origin.
float GetMotorSpeed() const
Get the motor speed, usually in radians per second.
const b2Vec2 & GetLocalAxisA() const
The local joint axis relative to bodyA.
virtual float GetReactionTorque(float inv_dt) const =0
Get the reaction torque on bodyB in N*m.
A rigid body. These are created via b2World::CreateBody.
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin.
float maxMotorTorque
The maximum motor torque, usually in N-m.
virtual b2Vec2 GetAnchorA() const =0
Get the anchor point on bodyA in world coordinates.
virtual void InitVelocityConstraints(const b2SolverData &data)=0
b2Vec2 localAxisA
The local translation axis in bodyA.
virtual bool SolvePositionConstraints(const b2SolverData &data)=0
const b2Vec2 & GetLocalAnchorA() const
The local anchor point relative to bodyA's origin.
bool enableMotor
Enable/disable the joint motor.
IMGUI_API void Initialize(ImGuiContext *context)
bool enableLimit
Enable/disable the joint limit.
virtual void Dump()
Dump this joint to the log file.
virtual b2Vec2 GetAnchorB() const =0
Get the anchor point on bodyB in world coordinates.
virtual void Draw(b2Draw *draw) const
Debug draw this joint.
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin.
float motorSpeed
The desired motor speed in radians per second.
float damping
Suspension damping. Typically in units of N*s/m.
float stiffness
Suspension stiffness. Typically in units N/m.
float GetMaxMotorTorque() const
float upperTranslation
The upper translation limit, usually in meters.