57 position.Set(0.0
f, 0.0
f);
59 linearVelocity.Set(0.0
f, 0.0
f);
60 angularVelocity = 0.0f;
62 angularDamping = 0.0f;
65 fixedRotation =
false;
163 void SetTransform(
const b2Vec2& position,
float angle);
171 const b2Vec2& GetPosition()
const;
175 float GetAngle()
const;
178 const b2Vec2& GetWorldCenter()
const;
181 const b2Vec2& GetLocalCenter()
const;
185 void SetLinearVelocity(
const b2Vec2& v);
189 const b2Vec2& GetLinearVelocity()
const;
193 void SetAngularVelocity(
float omega);
197 float GetAngularVelocity()
const;
210 void ApplyForceToCenter(
const b2Vec2& force,
bool wake);
216 void ApplyTorque(
float torque,
bool wake);
224 void ApplyLinearImpulse(
const b2Vec2& impulse,
const b2Vec2& point,
bool wake);
229 void ApplyLinearImpulseToCenter(
const b2Vec2& impulse,
bool wake);
234 void ApplyAngularImpulse(
float impulse,
bool wake);
238 float GetMass()
const;
242 float GetInertia()
const;
258 void ResetMassData();
283 b2Vec2 GetLinearVelocityFromWorldPoint(
const b2Vec2& worldPoint)
const;
288 b2Vec2 GetLinearVelocityFromLocalPoint(
const b2Vec2& localPoint)
const;
291 float GetLinearDamping()
const;
294 void SetLinearDamping(
float linearDamping);
297 float GetAngularDamping()
const;
300 void SetAngularDamping(
float angularDamping);
303 float GetGravityScale()
const;
306 void SetGravityScale(
float scale);
315 void SetBullet(
bool flag);
318 bool IsBullet()
const;
322 void SetSleepingAllowed(
bool flag);
325 bool IsSleepingAllowed()
const;
330 void SetAwake(
bool flag);
334 bool IsAwake()
const;
348 void SetEnabled(
bool flag);
351 bool IsEnabled()
const;
355 void SetFixedRotation(
bool flag);
358 bool IsFixedRotation()
const;
376 const b2Body* GetNext()
const;
382 void SetUserData(
void* data);
386 const b2World* GetWorld()
const;
407 friend class b2RopeJoint;
414 e_islandFlag = 0x0001,
415 e_awakeFlag = 0x0002,
416 e_autoSleepFlag = 0x0004,
417 e_bulletFlag = 0x0008,
418 e_fixedRotationFlag = 0x0010,
419 e_enabledFlag = 0x0020,
426 void SynchronizeFixtures();
427 void SynchronizeTransform();
431 bool ShouldCollide(
const b2Body* other)
const;
433 void Advance(
float t);
501 return m_sweep.localCenter;
516 m_linearVelocity = v;
521 return m_linearVelocity;
536 m_angularVelocity = w;
541 return m_angularVelocity;
551 return m_I +
m_mass *
b2Dot(m_sweep.localCenter, m_sweep.localCenter);
557 data->
I = m_I +
m_mass *
b2Dot(m_sweep.localCenter, m_sweep.localCenter);
558 data->
center = m_sweep.localCenter;
563 return b2Mul(m_xf, localPoint);
568 return b2Mul(m_xf.q, localVector);
573 return b2MulT(m_xf, worldPoint);
578 return b2MulT(m_xf.q, worldVector);
583 return m_linearVelocity +
b2Cross(m_angularVelocity, worldPoint - m_sweep.c);
588 return GetLinearVelocityFromWorldPoint(GetWorldPoint(localPoint));
593 return m_linearDamping;
598 m_linearDamping = linearDamping;
603 return m_angularDamping;
608 m_angularDamping = angularDamping;
613 return m_gravityScale;
618 m_gravityScale = scale;
625 m_flags |= e_bulletFlag;
629 m_flags &= ~e_bulletFlag;
635 return (m_flags & e_bulletFlag) == e_bulletFlag;
647 m_flags |= e_awakeFlag;
652 m_flags &= ~e_awakeFlag;
654 m_linearVelocity.SetZero();
655 m_angularVelocity = 0.0f;
663 return (m_flags & e_awakeFlag) == e_awakeFlag;
668 return (m_flags & e_enabledFlag) == e_enabledFlag;
673 return (m_flags & e_fixedRotationFlag) == e_fixedRotationFlag;
680 m_flags |= e_autoSleepFlag;
684 m_flags &= ~e_autoSleepFlag;
691 return (m_flags & e_autoSleepFlag) == e_autoSleepFlag;
696 return m_fixtureList;
701 return m_fixtureList;
716 return m_contactList;
721 return m_contactList;
746 if (wake && (m_flags & e_awakeFlag) == 0)
752 if (m_flags & e_awakeFlag)
755 m_torque +=
b2Cross(point - m_sweep.c, force);
766 if (wake && (m_flags & e_awakeFlag) == 0)
772 if (m_flags & e_awakeFlag)
785 if (wake && (m_flags & e_awakeFlag) == 0)
791 if (m_flags & e_awakeFlag)
804 if (wake && (m_flags & e_awakeFlag) == 0)
810 if (m_flags & e_awakeFlag)
812 m_linearVelocity += m_invMass * impulse;
813 m_angularVelocity += m_invI *
b2Cross(point - m_sweep.c, impulse);
824 if (wake && (m_flags & e_awakeFlag) == 0)
830 if (m_flags & e_awakeFlag)
832 m_linearVelocity += m_invMass * impulse;
843 if (wake && (m_flags & e_awakeFlag) == 0)
849 if (m_flags & e_awakeFlag)
851 m_angularVelocity += m_invI * impulse;
857 m_xf.q.Set(m_sweep.a);
858 m_xf.p = m_sweep.c -
b2Mul(m_xf.q, m_sweep.localCenter);
864 m_sweep.Advance(alpha);
865 m_sweep.c = m_sweep.c0;
866 m_sweep.a = m_sweep.a0;
867 m_xf.q.Set(m_sweep.a);
868 m_xf.p = m_sweep.c -
b2Mul(m_xf.q, m_sweep.localCenter);
const b2Transform & GetTransform() const
b2BodyDef()
This constructor sets the body definition default values.
bool IsFixedRotation() const
Does this body have fixed rotation?
This is an internal class.
float mass
The mass of the shape, usually in kilograms.
void ApplyLinearImpulseToCenter(const b2Vec2 &impulse, bool wake)
bool fixedRotation
Should this body be prevented from rotating? Useful for characters.
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
const b2Vec2 & GetLocalCenter() const
Get the local position of the center of mass.
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
b2BodyUserData m_userData
void ApplyForceToCenter(const b2Vec2 &force, bool wake)
void SetGravityScale(float scale)
Set the gravity scale of the body.
float GetGravityScale() const
Get the gravity scale of the body.
bool IsBullet() const
Is this body treated like a bullet for continuous collision detection?
bool IsSleepingAllowed() const
Is this body allowed to sleep.
float GetAngularVelocity() const
void ApplyForce(const b2Vec2 &force, const b2Vec2 &point, bool wake)
b2ContactEdge * GetContactList()
b2ContactEdge * m_contactList
You can define this to inject whatever data you want in b2Body.
void SetSleepingAllowed(bool flag)
const b2Vec2 & GetPosition() const
float angularVelocity
The angular velocity of the body.
b2Vec2 center
The position of the shape's centroid relative to the shape's origin.
b2BodyUserData & GetUserData()
Get the user data pointer that was provided in the body definition.
b2JointEdge * GetJointList()
Get the list of all joints attached to this body.
float GetLinearDamping() const
Get the linear damping of the body.
b2Vec2 linearVelocity
The linear velocity of the body's origin in world co-ordinates.
b2JointEdge * m_jointList
void SetBullet(bool flag)
Should this body be treated like a bullet for continuous collision detection?
A rigid body. These are created via b2World::CreateBody.
void SetLinearVelocity(const b2Vec2 &v)
const b2Vec2 & GetLinearVelocity() const
b2Vec2 GetLocalVector(const b2Vec2 &worldVector) const
float b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
b2Body * GetNext()
Get the next body in the world's body list.
b2Vec2 GetWorldVector(const b2Vec2 &localVector) const
void GetMassData(b2MassData *data) const
b2Vec2 GetLinearVelocityFromLocalPoint(const b2Vec2 &localPoint) const
bool enabled
Does this body start out enabled?
bool awake
Is this body initially awake or sleeping?
b2BodyType GetType() const
Get the type of this body.
b2BodyUserData userData
Use this to store application specific body data.
b2Vec2 GetLinearVelocityFromWorldPoint(const b2Vec2 &worldPoint) const
float angle
The world angle of the body in radians.
void SynchronizeTransform()
void SetLinearDamping(float linearDamping)
Set the linear damping of the body.
float I
The rotational inertia of the shape about the local origin.
float GetAngularDamping() const
Get the angular damping of the body.
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const
float gravityScale
Scale the gravity applied to this body.
void ApplyTorque(float torque, bool wake)
b2Vec2 b2MulT(const b2Mat22 &A, const b2Vec2 &v)
void ApplyAngularImpulse(float impulse, bool wake)
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const
void SetAngularVelocity(float omega)
b2JointUserData m_userData
b2Fixture * GetFixtureList()
Get the list of all fixtures attached to this body.
void SetAngularDamping(float angularDamping)
Set the angular damping of the body.
void ApplyLinearImpulse(const b2Vec2 &impulse, const b2Vec2 &point, bool wake)
bool IsEnabled() const
Get the active state of the body.
This holds the mass data computed for a shape.
const b2Vec2 & GetWorldCenter() const
Get the world position of the center of mass.
b2World * GetWorld()
Get the parent world of this body.
b2Fixture * m_fixtureList