19 #ifndef B2_PRISMATIC_JOINT_H 20 #define B2_PRISMATIC_JOINT_H 108 float32 GetJointTranslation()
const;
114 bool IsLimitEnabled()
const;
117 void EnableLimit(
bool flag);
129 bool IsMotorEnabled()
const;
132 void EnableMotor(
bool flag);
135 void SetMotorSpeed(
float32 speed);
141 void SetMaxMotorForce(
float32 force);
float32 referenceAngle
The constrained angle between the bodies: bodyB_angle - bodyA_angle.
float32 GetReferenceAngle() const
Get the reference angle.
Joint definitions are used to construct joints.
bool SolvePositionConstraints(const b2SolverData &data)
void SolveVelocityConstraints(const b2SolverData &data)
const b2Vec2 & GetLocalAnchorB() const
The local anchor point relative to bodyB's origin.
float32 upperTranslation
The upper translation limit, usually in meters.
b2Vec2 localAxisA
The local translation unit axis in bodyA.
void SetZero()
Set this vector to all zeros.
A 2D column vector with 3 elements.
A rigid body. These are created via b2World::CreateBody.
float32 GetMaxMotorForce() const
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin.
bool enableLimit
Enable/disable the joint limit.
void Initialize(b2Body *bodyA, b2Body *bodyB, const b2Vec2 &anchor, const b2Vec2 &axis)
float32 m_upperTranslation
A 3-by-3 matrix. Stored in column-major order.
const b2Vec2 & GetLocalAxisA() const
The local joint axis relative to bodyA.
const b2Vec2 & GetLocalAnchorA() const
The local anchor point relative to bodyA's origin.
float32 GetMotorSpeed() const
Get the motor speed, usually in meters per second.
b2JointType type
The joint type is set automatically for concrete joint types.
float32 motorSpeed
The desired motor speed in radians per second.
bool enableMotor
Enable/disable the joint motor.
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin.
b2LimitState m_limitState
float32 m_lowerTranslation
b2Body * bodyA
The first attached body.
void Set(float32 x_, float32 y_)
Set this vector to some specified coordinates.
float32 lowerTranslation
The lower translation limit, usually in meters.
b2Body * bodyB
The second attached body.
void InitVelocityConstraints(const b2SolverData &data)
float32 maxMotorForce
The maximum motor torque, usually in N-m.