Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
b2WheelJoint Class Reference

#include <b2_wheel_joint.h>

Inheritance diagram for b2WheelJoint:
Inheritance graph
[legend]

Public Member Functions

void Draw (b2Draw *draw) const override
 Debug draw this joint. More...
 
void Dump () override
 Dump to b2Log. More...
 
void EnableLimit (bool flag)
 Enable/disable the joint translation limit. More...
 
void EnableMotor (bool flag)
 Enable/disable the joint motor. More...
 
b2Vec2 GetAnchorA () const override
 Get the anchor point on bodyA in world coordinates. More...
 
b2Vec2 GetAnchorB () const override
 Get the anchor point on bodyB in world coordinates. More...
 
float GetDamping () const
 
float GetJointAngle () const
 Get the current joint angle in radians. More...
 
float GetJointAngularSpeed () const
 Get the current joint angular speed in radians per second. More...
 
float GetJointLinearSpeed () const
 Get the current joint linear speed, usually in meters per second. More...
 
float GetJointTranslation () const
 Get the current joint translation, usually in meters. More...
 
const b2Vec2GetLocalAnchorA () const
 The local anchor point relative to bodyA's origin. More...
 
const b2Vec2GetLocalAnchorB () const
 The local anchor point relative to bodyB's origin. More...
 
const b2Vec2GetLocalAxisA () const
 The local joint axis relative to bodyA. More...
 
float GetLowerLimit () const
 Get the lower joint translation limit, usually in meters. More...
 
float GetMaxMotorTorque () const
 
float GetMotorSpeed () const
 Get the motor speed, usually in radians per second. More...
 
float GetMotorTorque (float inv_dt) const
 Get the current motor torque given the inverse time step, usually in N-m. More...
 
b2Vec2 GetReactionForce (float inv_dt) const override
 Get the reaction force on bodyB at the joint anchor in Newtons. More...
 
float GetReactionTorque (float inv_dt) const override
 Get the reaction torque on bodyB in N*m. More...
 
float GetStiffness () const
 
float GetUpperLimit () const
 Get the upper joint translation limit, usually in meters. More...
 
bool IsLimitEnabled () const
 Is the joint limit enabled? More...
 
bool IsMotorEnabled () const
 Is the joint motor enabled? More...
 
void SetDamping (float damping)
 Access damping. More...
 
void SetLimits (float lower, float upper)
 Set the joint translation limits, usually in meters. More...
 
void SetMaxMotorTorque (float torque)
 Set/Get the maximum motor force, usually in N-m. More...
 
void SetMotorSpeed (float speed)
 Set the motor speed, usually in radians per second. More...
 
void SetStiffness (float stiffness)
 Access spring stiffness. More...
 
- Public Member Functions inherited from b2Joint
b2BodyGetBodyA ()
 Get the first body attached to this joint. More...
 
b2BodyGetBodyB ()
 Get the second body attached to this joint. More...
 
bool GetCollideConnected () const
 
b2JointGetNext ()
 Get the next joint the world joint list. More...
 
const b2JointGetNext () const
 
b2JointType GetType () const
 Get the type of the concrete joint. More...
 
b2JointUserDataGetUserData ()
 Get the user data pointer. More...
 
bool IsEnabled () const
 Short-cut function to determine if either body is enabled. More...
 
virtual void ShiftOrigin (const b2Vec2 &newOrigin)
 Shift the origin for any points stored in world coordinates. More...
 

Protected Member Functions

 b2WheelJoint (const b2WheelJointDef *def)
 
void InitVelocityConstraints (const b2SolverData &data) override
 
bool SolvePositionConstraints (const b2SolverData &data) override
 
void SolveVelocityConstraints (const b2SolverData &data) override
 
- Protected Member Functions inherited from b2Joint
 b2Joint (const b2JointDef *def)
 
virtual ~b2Joint ()
 

Protected Attributes

b2Vec2 m_ax
 
float m_axialMass
 
b2Vec2 m_ay
 
float m_bias
 
float m_damping
 
bool m_enableLimit
 
bool m_enableMotor
 
float m_gamma
 
float m_impulse
 
int32 m_indexA
 
int32 m_indexB
 
float m_invIA
 
float m_invIB
 
float m_invMassA
 
float m_invMassB
 
b2Vec2 m_localAnchorA
 
b2Vec2 m_localAnchorB
 
b2Vec2 m_localCenterA
 
b2Vec2 m_localCenterB
 
b2Vec2 m_localXAxisA
 
b2Vec2 m_localYAxisA
 
float m_lowerImpulse
 
float m_lowerTranslation
 
float m_mass
 
float m_maxMotorTorque
 
float m_motorImpulse
 
float m_motorMass
 
float m_motorSpeed
 
float m_sAx
 
float m_sAy
 
float m_sBx
 
float m_sBy
 
float m_springImpulse
 
float m_springMass
 
float m_stiffness
 
float m_translation
 
float m_upperImpulse
 
float m_upperTranslation
 
- Protected Attributes inherited from b2Joint
b2Bodym_bodyA
 
b2Bodym_bodyB
 
bool m_collideConnected
 
b2JointEdge m_edgeA
 
b2JointEdge m_edgeB
 
int32 m_index
 
bool m_islandFlag
 
b2Jointm_next
 
b2Jointm_prev
 
b2JointType m_type
 
b2JointUserData m_userData
 

Friends

class b2Joint
 

Additional Inherited Members

- Static Protected Member Functions inherited from b2Joint
static b2JointCreate (const b2JointDef *def, b2BlockAllocator *allocator)
 
static void Destroy (b2Joint *joint, b2BlockAllocator *allocator)
 

Detailed Description

A wheel joint. This joint provides two degrees of freedom: translation along an axis fixed in bodyA and rotation in the plane. In other words, it is a point to line constraint with a rotational motor and a linear spring/damper. The spring/damper is initialized upon creation. This joint is designed for vehicle suspensions.

Definition at line 95 of file b2_wheel_joint.h.

Constructor & Destructor Documentation

◆ b2WheelJoint()

b2WheelJoint::b2WheelJoint ( const b2WheelJointDef def)
protected

Definition at line 53 of file b2_wheel_joint.cpp.

Member Function Documentation

◆ Draw()

void b2WheelJoint::Draw ( b2Draw draw) const
overridevirtual

Debug draw this joint.

Reimplemented from b2Joint.

Definition at line 639 of file b2_wheel_joint.cpp.

◆ Dump()

void b2WheelJoint::Dump ( )
overridevirtual

Dump to b2Log.

Reimplemented from b2Joint.

Definition at line 616 of file b2_wheel_joint.cpp.

◆ EnableLimit()

void b2WheelJoint::EnableLimit ( bool  flag)

Enable/disable the joint translation limit.

Definition at line 520 of file b2_wheel_joint.cpp.

◆ EnableMotor()

void b2WheelJoint::EnableMotor ( bool  flag)

Enable/disable the joint motor.

Definition at line 561 of file b2_wheel_joint.cpp.

◆ GetAnchorA()

b2Vec2 b2WheelJoint::GetAnchorA ( ) const
overridevirtual

Get the anchor point on bodyA in world coordinates.

Implements b2Joint.

Definition at line 446 of file b2_wheel_joint.cpp.

◆ GetAnchorB()

b2Vec2 b2WheelJoint::GetAnchorB ( ) const
overridevirtual

Get the anchor point on bodyB in world coordinates.

Implements b2Joint.

Definition at line 451 of file b2_wheel_joint.cpp.

◆ GetDamping()

float b2WheelJoint::GetDamping ( ) const

Definition at line 611 of file b2_wheel_joint.cpp.

◆ GetJointAngle()

float b2WheelJoint::GetJointAngle ( ) const

Get the current joint angle in radians.

Definition at line 501 of file b2_wheel_joint.cpp.

◆ GetJointAngularSpeed()

float b2WheelJoint::GetJointAngularSpeed ( ) const

Get the current joint angular speed in radians per second.

Definition at line 508 of file b2_wheel_joint.cpp.

◆ GetJointLinearSpeed()

float b2WheelJoint::GetJointLinearSpeed ( ) const

Get the current joint linear speed, usually in meters per second.

Definition at line 480 of file b2_wheel_joint.cpp.

◆ GetJointTranslation()

float b2WheelJoint::GetJointTranslation ( ) const

Get the current joint translation, usually in meters.

Definition at line 466 of file b2_wheel_joint.cpp.

◆ GetLocalAnchorA()

const b2Vec2& b2WheelJoint::GetLocalAnchorA ( ) const
inline

The local anchor point relative to bodyA's origin.

Definition at line 105 of file b2_wheel_joint.h.

◆ GetLocalAnchorB()

const b2Vec2& b2WheelJoint::GetLocalAnchorB ( ) const
inline

The local anchor point relative to bodyB's origin.

Definition at line 108 of file b2_wheel_joint.h.

◆ GetLocalAxisA()

const b2Vec2& b2WheelJoint::GetLocalAxisA ( ) const
inline

The local joint axis relative to bodyA.

Definition at line 111 of file b2_wheel_joint.h.

◆ GetLowerLimit()

float b2WheelJoint::GetLowerLimit ( ) const

Get the lower joint translation limit, usually in meters.

Definition at line 532 of file b2_wheel_joint.cpp.

◆ GetMaxMotorTorque()

float b2WheelJoint::GetMaxMotorTorque ( ) const
inline

Definition at line 235 of file b2_wheel_joint.h.

◆ GetMotorSpeed()

float b2WheelJoint::GetMotorSpeed ( ) const
inline

Get the motor speed, usually in radians per second.

Definition at line 230 of file b2_wheel_joint.h.

◆ GetMotorTorque()

float b2WheelJoint::GetMotorTorque ( float  inv_dt) const

Get the current motor torque given the inverse time step, usually in N-m.

Definition at line 591 of file b2_wheel_joint.cpp.

◆ GetReactionForce()

b2Vec2 b2WheelJoint::GetReactionForce ( float  inv_dt) const
overridevirtual

Get the reaction force on bodyB at the joint anchor in Newtons.

Implements b2Joint.

Definition at line 456 of file b2_wheel_joint.cpp.

◆ GetReactionTorque()

float b2WheelJoint::GetReactionTorque ( float  inv_dt) const
overridevirtual

Get the reaction torque on bodyB in N*m.

Implements b2Joint.

Definition at line 461 of file b2_wheel_joint.cpp.

◆ GetStiffness()

float b2WheelJoint::GetStiffness ( ) const

Definition at line 601 of file b2_wheel_joint.cpp.

◆ GetUpperLimit()

float b2WheelJoint::GetUpperLimit ( ) const

Get the upper joint translation limit, usually in meters.

Definition at line 537 of file b2_wheel_joint.cpp.

◆ InitVelocityConstraints()

void b2WheelJoint::InitVelocityConstraints ( const b2SolverData data)
overrideprotectedvirtual

Implements b2Joint.

Definition at line 89 of file b2_wheel_joint.cpp.

◆ IsLimitEnabled()

bool b2WheelJoint::IsLimitEnabled ( ) const

Is the joint limit enabled?

Definition at line 515 of file b2_wheel_joint.cpp.

◆ IsMotorEnabled()

bool b2WheelJoint::IsMotorEnabled ( ) const

Is the joint motor enabled?

Definition at line 556 of file b2_wheel_joint.cpp.

◆ SetDamping()

void b2WheelJoint::SetDamping ( float  damping)

Access damping.

Definition at line 606 of file b2_wheel_joint.cpp.

◆ SetLimits()

void b2WheelJoint::SetLimits ( float  lower,
float  upper 
)

Set the joint translation limits, usually in meters.

Definition at line 542 of file b2_wheel_joint.cpp.

◆ SetMaxMotorTorque()

void b2WheelJoint::SetMaxMotorTorque ( float  torque)

Set/Get the maximum motor force, usually in N-m.

Definition at line 581 of file b2_wheel_joint.cpp.

◆ SetMotorSpeed()

void b2WheelJoint::SetMotorSpeed ( float  speed)

Set the motor speed, usually in radians per second.

Definition at line 571 of file b2_wheel_joint.cpp.

◆ SetStiffness()

void b2WheelJoint::SetStiffness ( float  stiffness)

Access spring stiffness.

Definition at line 596 of file b2_wheel_joint.cpp.

◆ SolvePositionConstraints()

bool b2WheelJoint::SolvePositionConstraints ( const b2SolverData data)
overrideprotectedvirtual

Implements b2Joint.

Definition at line 344 of file b2_wheel_joint.cpp.

◆ SolveVelocityConstraints()

void b2WheelJoint::SolveVelocityConstraints ( const b2SolverData data)
overrideprotectedvirtual

Implements b2Joint.

Definition at line 237 of file b2_wheel_joint.cpp.

Friends And Related Function Documentation

◆ b2Joint

friend class b2Joint
friend

Definition at line 175 of file b2_wheel_joint.h.

Member Data Documentation

◆ m_ax

b2Vec2 b2WheelJoint::m_ax
protected

Definition at line 216 of file b2_wheel_joint.h.

◆ m_axialMass

float b2WheelJoint::m_axialMass
protected

Definition at line 222 of file b2_wheel_joint.h.

◆ m_ay

b2Vec2 b2WheelJoint::m_ay
protected

Definition at line 216 of file b2_wheel_joint.h.

◆ m_bias

float b2WheelJoint::m_bias
protected

Definition at line 225 of file b2_wheel_joint.h.

◆ m_damping

float b2WheelJoint::m_damping
protected

Definition at line 204 of file b2_wheel_joint.h.

◆ m_enableLimit

bool b2WheelJoint::m_enableLimit
protected

Definition at line 200 of file b2_wheel_joint.h.

◆ m_enableMotor

bool b2WheelJoint::m_enableMotor
protected

Definition at line 201 of file b2_wheel_joint.h.

◆ m_gamma

float b2WheelJoint::m_gamma
protected

Definition at line 226 of file b2_wheel_joint.h.

◆ m_impulse

float b2WheelJoint::m_impulse
protected

Definition at line 187 of file b2_wheel_joint.h.

◆ m_indexA

int32 b2WheelJoint::m_indexA
protected

Definition at line 207 of file b2_wheel_joint.h.

◆ m_indexB

int32 b2WheelJoint::m_indexB
protected

Definition at line 208 of file b2_wheel_joint.h.

◆ m_invIA

float b2WheelJoint::m_invIA
protected

Definition at line 213 of file b2_wheel_joint.h.

◆ m_invIB

float b2WheelJoint::m_invIB
protected

Definition at line 214 of file b2_wheel_joint.h.

◆ m_invMassA

float b2WheelJoint::m_invMassA
protected

Definition at line 211 of file b2_wheel_joint.h.

◆ m_invMassB

float b2WheelJoint::m_invMassB
protected

Definition at line 212 of file b2_wheel_joint.h.

◆ m_localAnchorA

b2Vec2 b2WheelJoint::m_localAnchorA
protected

Definition at line 182 of file b2_wheel_joint.h.

◆ m_localAnchorB

b2Vec2 b2WheelJoint::m_localAnchorB
protected

Definition at line 183 of file b2_wheel_joint.h.

◆ m_localCenterA

b2Vec2 b2WheelJoint::m_localCenterA
protected

Definition at line 209 of file b2_wheel_joint.h.

◆ m_localCenterB

b2Vec2 b2WheelJoint::m_localCenterB
protected

Definition at line 210 of file b2_wheel_joint.h.

◆ m_localXAxisA

b2Vec2 b2WheelJoint::m_localXAxisA
protected

Definition at line 184 of file b2_wheel_joint.h.

◆ m_localYAxisA

b2Vec2 b2WheelJoint::m_localYAxisA
protected

Definition at line 185 of file b2_wheel_joint.h.

◆ m_lowerImpulse

float b2WheelJoint::m_lowerImpulse
protected

Definition at line 191 of file b2_wheel_joint.h.

◆ m_lowerTranslation

float b2WheelJoint::m_lowerTranslation
protected

Definition at line 194 of file b2_wheel_joint.h.

◆ m_mass

float b2WheelJoint::m_mass
protected

Definition at line 220 of file b2_wheel_joint.h.

◆ m_maxMotorTorque

float b2WheelJoint::m_maxMotorTorque
protected

Definition at line 197 of file b2_wheel_joint.h.

◆ m_motorImpulse

float b2WheelJoint::m_motorImpulse
protected

Definition at line 188 of file b2_wheel_joint.h.

◆ m_motorMass

float b2WheelJoint::m_motorMass
protected

Definition at line 221 of file b2_wheel_joint.h.

◆ m_motorSpeed

float b2WheelJoint::m_motorSpeed
protected

Definition at line 198 of file b2_wheel_joint.h.

◆ m_sAx

float b2WheelJoint::m_sAx
protected

Definition at line 217 of file b2_wheel_joint.h.

◆ m_sAy

float b2WheelJoint::m_sAy
protected

Definition at line 218 of file b2_wheel_joint.h.

◆ m_sBx

float b2WheelJoint::m_sBx
protected

Definition at line 217 of file b2_wheel_joint.h.

◆ m_sBy

float b2WheelJoint::m_sBy
protected

Definition at line 218 of file b2_wheel_joint.h.

◆ m_springImpulse

float b2WheelJoint::m_springImpulse
protected

Definition at line 189 of file b2_wheel_joint.h.

◆ m_springMass

float b2WheelJoint::m_springMass
protected

Definition at line 223 of file b2_wheel_joint.h.

◆ m_stiffness

float b2WheelJoint::m_stiffness
protected

Definition at line 203 of file b2_wheel_joint.h.

◆ m_translation

float b2WheelJoint::m_translation
protected

Definition at line 193 of file b2_wheel_joint.h.

◆ m_upperImpulse

float b2WheelJoint::m_upperImpulse
protected

Definition at line 192 of file b2_wheel_joint.h.

◆ m_upperTranslation

float b2WheelJoint::m_upperTranslation
protected

Definition at line 195 of file b2_wheel_joint.h.


The documentation for this class was generated from the following files:


mvsim
Author(s):
autogenerated on Tue Jul 4 2023 03:08:22