23 #ifndef B2_PRISMATIC_JOINT_H 24 #define B2_PRISMATIC_JOINT_H 40 localAnchorA.SetZero();
41 localAnchorB.SetZero();
42 localAxisA.Set(1.0
f, 0.0
f);
43 referenceAngle = 0.0f;
45 lowerTranslation = 0.0f;
46 upperTranslation = 0.0f;
113 float GetJointTranslation()
const;
116 float GetJointSpeed()
const;
119 bool IsLimitEnabled()
const;
122 void EnableLimit(
bool flag);
125 float GetLowerLimit()
const;
128 float GetUpperLimit()
const;
131 void SetLimits(
float lower,
float upper);
134 bool IsMotorEnabled()
const;
137 void EnableMotor(
bool flag);
140 void SetMotorSpeed(
float speed);
143 float GetMotorSpeed()
const;
146 void SetMaxMotorForce(
float force);
150 float GetMotorForce(
float inv_dt)
const;
153 void Dump()
override;
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.
b2Vec2 localAxisA
The local translation unit axis in bodyA.
float lowerTranslation
The lower translation limit, usually in meters.
float GetReferenceAngle() const
Get the reference angle.
virtual float GetReactionTorque(float inv_dt) const =0
Get the reaction torque on bodyB in N*m.
const b2Vec2 & GetLocalAxisA() const
The local joint axis relative to bodyA.
A rigid body. These are created via b2World::CreateBody.
float maxMotorForce
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 localAnchorB
The local anchor point relative to bodyB's origin.
float motorSpeed
The desired motor speed in radians per second.
virtual bool SolvePositionConstraints(const b2SolverData &data)=0
bool enableLimit
Enable/disable the joint limit.
IMGUI_API void Initialize(ImGuiContext *context)
virtual void Dump()
Dump this joint to the log file.
float upperTranslation
The upper translation limit, usually in meters.
float GetMaxMotorForce() const
const b2Vec2 & GetLocalAnchorB() const
The local anchor point relative to bodyB's origin.
const b2Vec2 & GetLocalAnchorA() const
The local anchor point relative to bodyA's origin.
virtual b2Vec2 GetAnchorB() const =0
Get the anchor point on bodyB in world coordinates.
float GetMotorSpeed() const
Get the motor speed, usually in meters per second.
bool enableMotor
Enable/disable the joint motor.
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin.
virtual void Draw(b2Draw *draw) const
Debug draw this joint.
A 2-by-2 matrix. Stored in column-major order.
float referenceAngle
The constrained angle between the bodies: bodyB_angle - bodyA_angle.