b2_revolute_joint.h
Go to the documentation of this file.
1 // MIT License
2 
3 // Copyright (c) 2019 Erin Catto
4 
5 // Permission is hereby granted, free of charge, to any person obtaining a copy
6 // of this software and associated documentation files (the "Software"), to deal
7 // in the Software without restriction, including without limitation the rights
8 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 // copies of the Software, and to permit persons to whom the Software is
10 // furnished to do so, subject to the following conditions:
11 
12 // The above copyright notice and this permission notice shall be included in all
13 // copies or substantial portions of the Software.
14 
15 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 // SOFTWARE.
22 
23 #ifndef B2_REVOLUTE_JOINT_H
24 #define B2_REVOLUTE_JOINT_H
25 
26 #include "b2_api.h"
27 #include "b2_joint.h"
28 
40 {
42  {
44  localAnchorA.Set(0.0f, 0.0f);
45  localAnchorB.Set(0.0f, 0.0f);
46  referenceAngle = 0.0f;
47  lowerAngle = 0.0f;
48  upperAngle = 0.0f;
49  maxMotorTorque = 0.0f;
50  motorSpeed = 0.0f;
51  enableLimit = false;
52  enableMotor = false;
53  }
54 
57  void Initialize(b2Body* bodyA, b2Body* bodyB, const b2Vec2& anchor);
58 
61 
64 
67 
70 
72  float lowerAngle;
73 
75  float upperAngle;
76 
79 
81  float motorSpeed;
82 
86 };
87 
95 {
96 public:
97  b2Vec2 GetAnchorA() const override;
98  b2Vec2 GetAnchorB() const override;
99 
101  const b2Vec2& GetLocalAnchorA() const { return m_localAnchorA; }
102 
104  const b2Vec2& GetLocalAnchorB() const { return m_localAnchorB; }
105 
107  float GetReferenceAngle() const { return m_referenceAngle; }
108 
110  float GetJointAngle() const;
111 
113  float GetJointSpeed() const;
114 
116  bool IsLimitEnabled() const;
117 
119  void EnableLimit(bool flag);
120 
122  float GetLowerLimit() const;
123 
125  float GetUpperLimit() const;
126 
128  void SetLimits(float lower, float upper);
129 
131  bool IsMotorEnabled() const;
132 
134  void EnableMotor(bool flag);
135 
137  void SetMotorSpeed(float speed);
138 
140  float GetMotorSpeed() const;
141 
143  void SetMaxMotorTorque(float torque);
144  float GetMaxMotorTorque() const { return m_maxMotorTorque; }
145 
148  b2Vec2 GetReactionForce(float inv_dt) const override;
149 
152  float GetReactionTorque(float inv_dt) const override;
153 
156  float GetMotorTorque(float inv_dt) const;
157 
159  void Dump() override;
160 
162  void Draw(b2Draw* draw) const override;
163 
164 protected:
165 
166  friend class b2Joint;
167  friend class b2GearJoint;
168 
170 
171  void InitVelocityConstraints(const b2SolverData& data) override;
172  void SolveVelocityConstraints(const b2SolverData& data) override;
173  bool SolvePositionConstraints(const b2SolverData& data) override;
174 
175  // Solver shared
189 
190  // Solver temp
197  float m_invMassA;
198  float m_invMassB;
199  float m_invIA;
200  float m_invIB;
202  float m_angle;
203  float m_axialMass;
204 };
205 
206 inline float b2RevoluteJoint::GetMotorSpeed() const
207 {
208  return m_motorSpeed;
209 }
210 
211 #endif
b2RevoluteJoint::m_indexA
int32 m_indexA
Definition: b2_revolute_joint.h:191
b2RevoluteJoint::m_localCenterB
b2Vec2 m_localCenterB
Definition: b2_revolute_joint.h:196
b2_api.h
b2RevoluteJoint::m_localAnchorB
b2Vec2 m_localAnchorB
Definition: b2_revolute_joint.h:177
b2Joint::GetReactionTorque
virtual float GetReactionTorque(float inv_dt) const =0
Get the reaction torque on bodyB in N*m.
b2RevoluteJoint
Definition: b2_revolute_joint.h:94
b2RevoluteJoint::m_maxMotorTorque
float m_maxMotorTorque
Definition: b2_revolute_joint.h:183
b2RevoluteJointDef::b2RevoluteJointDef
b2RevoluteJointDef()
Definition: b2_revolute_joint.h:41
b2Joint::SolvePositionConstraints
virtual bool SolvePositionConstraints(const b2SolverData &data)=0
b2SolverData
Solver Data.
Definition: b2_time_step.h:67
b2_joint.h
b2RevoluteJoint::m_enableMotor
bool m_enableMotor
Definition: b2_revolute_joint.h:182
b2Joint::InitVelocityConstraints
virtual void InitVelocityConstraints(const b2SolverData &data)=0
b2RevoluteJoint::m_rB
b2Vec2 m_rB
Definition: b2_revolute_joint.h:194
b2Mat22
A 2-by-2 matrix. Stored in column-major order.
Definition: b2_math.h:171
b2RevoluteJoint::m_upperImpulse
float m_upperImpulse
Definition: b2_revolute_joint.h:181
b2RevoluteJoint::m_invMassB
float m_invMassB
Definition: b2_revolute_joint.h:198
b2Body
A rigid body. These are created via b2World::CreateBody.
Definition: b2_body.h:128
b2RevoluteJoint::m_localAnchorA
b2Vec2 m_localAnchorA
Definition: b2_revolute_joint.h:176
B2_API
#define B2_API
Definition: b2_api.h:49
b2RevoluteJoint::m_invIB
float m_invIB
Definition: b2_revolute_joint.h:200
b2Joint::Draw
virtual void Draw(b2Draw *draw) const
Debug draw this joint.
Definition: b2_joint.cpp:255
b2Vec2
A 2D column vector.
Definition: b2_math.h:41
b2Joint::Dump
virtual void Dump()
Dump this joint to the log file.
Definition: b2_joint.h:151
b2RevoluteJointDef
Definition: b2_revolute_joint.h:39
f
f
b2RevoluteJoint::GetMotorSpeed
float GetMotorSpeed() const
Get the motor speed in radians per second.
Definition: b2_revolute_joint.h:206
b2Joint::SolveVelocityConstraints
virtual void SolveVelocityConstraints(const b2SolverData &data)=0
b2RevoluteJoint::m_K
b2Mat22 m_K
Definition: b2_revolute_joint.h:201
b2RevoluteJoint::m_localCenterA
b2Vec2 m_localCenterA
Definition: b2_revolute_joint.h:195
b2Joint::GetAnchorA
virtual b2Vec2 GetAnchorA() const =0
Get the anchor point on bodyA in world coordinates.
b2Joint
Definition: b2_joint.h:110
b2Draw
Definition: b2_draw.h:48
b2RevoluteJointDef::enableMotor
bool enableMotor
A flag to enable the joint motor.
Definition: b2_revolute_joint.h:78
b2RevoluteJointDef::referenceAngle
float referenceAngle
The bodyB angle minus bodyA angle in the reference state (radians).
Definition: b2_revolute_joint.h:66
b2RevoluteJointDef::upperAngle
float upperAngle
The upper angle for the joint limit (radians).
Definition: b2_revolute_joint.h:75
b2RevoluteJoint::m_referenceAngle
float m_referenceAngle
Definition: b2_revolute_joint.h:186
b2JointDef
Joint definitions are used to construct joints.
Definition: b2_joint.h:72
b2RevoluteJoint::GetReferenceAngle
float GetReferenceAngle() const
Get the reference angle.
Definition: b2_revolute_joint.h:107
b2RevoluteJointDef::localAnchorB
b2Vec2 localAnchorB
The local anchor point relative to bodyB's origin.
Definition: b2_revolute_joint.h:63
b2RevoluteJoint::m_invIA
float m_invIA
Definition: b2_revolute_joint.h:199
b2RevoluteJoint::m_upperAngle
float m_upperAngle
Definition: b2_revolute_joint.h:188
b2RevoluteJoint::m_enableLimit
bool m_enableLimit
Definition: b2_revolute_joint.h:185
b2RevoluteJoint::GetLocalAnchorB
const b2Vec2 & GetLocalAnchorB() const
The local anchor point relative to bodyB's origin.
Definition: b2_revolute_joint.h:104
b2RevoluteJoint::m_motorSpeed
float m_motorSpeed
Definition: b2_revolute_joint.h:184
b2RevoluteJoint::GetMaxMotorTorque
float GetMaxMotorTorque() const
Definition: b2_revolute_joint.h:144
b2RevoluteJoint::m_lowerAngle
float m_lowerAngle
Definition: b2_revolute_joint.h:187
b2RevoluteJointDef::enableLimit
bool enableLimit
A flag to enable joint limits.
Definition: b2_revolute_joint.h:69
b2RevoluteJoint::m_angle
float m_angle
Definition: b2_revolute_joint.h:202
b2RevoluteJoint::GetLocalAnchorA
const b2Vec2 & GetLocalAnchorA() const
The local anchor point relative to bodyA's origin.
Definition: b2_revolute_joint.h:101
ImGui::Initialize
IMGUI_API void Initialize(ImGuiContext *context)
Definition: imgui.cpp:3473
int32
signed int int32
Definition: b2_types.h:28
type
GLenum type
Definition: gl.h:1033
b2RevoluteJointDef::motorSpeed
float motorSpeed
The desired motor speed. Usually in radians per second.
Definition: b2_revolute_joint.h:81
b2Joint::GetAnchorB
virtual b2Vec2 GetAnchorB() const =0
Get the anchor point on bodyB in world coordinates.
b2RevoluteJoint::m_impulse
b2Vec2 m_impulse
Definition: b2_revolute_joint.h:178
b2RevoluteJoint::m_motorImpulse
float m_motorImpulse
Definition: b2_revolute_joint.h:179
b2RevoluteJoint::m_lowerImpulse
float m_lowerImpulse
Definition: b2_revolute_joint.h:180
b2RevoluteJointDef::localAnchorA
b2Vec2 localAnchorA
The local anchor point relative to bodyA's origin.
Definition: b2_revolute_joint.h:60
b2RevoluteJoint::m_rA
b2Vec2 m_rA
Definition: b2_revolute_joint.h:193
e_revoluteJoint
@ e_revoluteJoint
Definition: b2_joint.h:38
b2GearJoint
Definition: b2_gear_joint.h:61
b2RevoluteJoint::m_indexB
int32 m_indexB
Definition: b2_revolute_joint.h:192
b2RevoluteJointDef::maxMotorTorque
float maxMotorTorque
Definition: b2_revolute_joint.h:85
b2RevoluteJoint::m_invMassA
float m_invMassA
Definition: b2_revolute_joint.h:197
b2RevoluteJointDef::lowerAngle
float lowerAngle
The lower angle for the joint limit (radians).
Definition: b2_revolute_joint.h:72
b2Joint::GetReactionForce
virtual b2Vec2 GetReactionForce(float inv_dt) const =0
Get the reaction force on bodyB at the joint anchor in Newtons.
b2RevoluteJoint::m_axialMass
float m_axialMass
Definition: b2_revolute_joint.h:203


mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:07