169         const b2Vec2& GetPosition() 
const;
   176         const b2Vec2& GetWorldCenter() 
const;
   179         const b2Vec2& GetLocalCenter() 
const;
   183         void SetLinearVelocity(
const b2Vec2& 
v);
   187         const b2Vec2& GetLinearVelocity() 
const;
   191         void SetAngularVelocity(
float32 omega);
   195         float32 GetAngularVelocity() 
const;
   203         void ApplyForce(
const b2Vec2& force, 
const b2Vec2& point, 
bool wake);
   208         void ApplyForceToCenter(
const b2Vec2& force, 
bool wake);
   215         void ApplyTorque(
float32 torque, 
bool wake);
   223         void ApplyLinearImpulse(
const b2Vec2& impulse, 
const b2Vec2& point, 
bool wake);
   228         void ApplyAngularImpulse(
float32 impulse, 
bool wake);
   252         void ResetMassData();
   277         b2Vec2 GetLinearVelocityFromWorldPoint(
const b2Vec2& worldPoint) 
const;
   282         b2Vec2 GetLinearVelocityFromLocalPoint(
const b2Vec2& localPoint) 
const;
   285         float32 GetLinearDamping() 
const;
   291         float32 GetAngularDamping() 
const;
   297         float32 GetGravityScale() 
const;
   309         void SetBullet(
bool flag);
   312         bool IsBullet() 
const;
   316         void SetSleepingAllowed(
bool flag);
   319         bool IsSleepingAllowed() 
const;
   324         void SetAwake(
bool flag);
   328         bool IsAwake() 
const;
   343         void SetActive(
bool flag);
   346         bool IsActive() 
const;
   350         void SetFixedRotation(
bool flag);
   353         bool IsFixedRotation() 
const;
   371         const b2Body* GetNext() 
const;
   374         void* GetUserData() 
const;
   377         void SetUserData(
void* data);
   381         const b2World* GetWorld() 
const;
   409                 e_islandFlag            = 0x0001,
   410                 e_awakeFlag                     = 0x0002,
   411                 e_autoSleepFlag         = 0x0004,
   412                 e_bulletFlag            = 0x0008,
   413                 e_fixedRotationFlag     = 0x0010,
   414                 e_activeFlag            = 0x0020,
   421         void SynchronizeFixtures();
   422         void SynchronizeTransform();
   426         bool ShouldCollide(
const b2Body* other) 
const;
   496         return m_sweep.localCenter;
   511         m_linearVelocity = v;
   516         return m_linearVelocity;
   531         m_angularVelocity = w;
   536         return m_angularVelocity;
   546         return m_I + 
m_mass * 
b2Dot(m_sweep.localCenter, m_sweep.localCenter);
   552         data->
I = m_I + 
m_mass * 
b2Dot(m_sweep.localCenter, m_sweep.localCenter);
   553         data->
center = m_sweep.localCenter;
   558         return b2Mul(m_xf, localPoint);
   563         return b2Mul(m_xf.q, localVector);
   568         return b2MulT(m_xf, worldPoint);
   573         return b2MulT(m_xf.q, worldVector);
   578         return m_linearVelocity + 
b2Cross(m_angularVelocity, worldPoint - m_sweep.c);
   583         return GetLinearVelocityFromWorldPoint(GetWorldPoint(localPoint));
   588         return m_linearDamping;
   598         return m_angularDamping;
   608         return m_gravityScale;
   613         m_gravityScale = scale;
   620                 m_flags |= e_bulletFlag;
   624                 m_flags &= ~e_bulletFlag;
   630         return (m_flags & e_bulletFlag) == e_bulletFlag;
   637                 if ((m_flags & e_awakeFlag) == 0)
   639                         m_flags |= e_awakeFlag;
   645                 m_flags &= ~e_awakeFlag;
   647                 m_linearVelocity.SetZero();
   648                 m_angularVelocity = 0.0f;
   656         return (m_flags & e_awakeFlag) == e_awakeFlag;
   661         return (m_flags & e_activeFlag) == e_activeFlag;
   666         return (m_flags & e_fixedRotationFlag) == e_fixedRotationFlag;
   673                 m_flags |= e_autoSleepFlag;
   677                 m_flags &= ~e_autoSleepFlag;
   684         return (m_flags & e_autoSleepFlag) == e_autoSleepFlag;
   689         return m_fixtureList;
   694         return m_fixtureList;
   709         return m_contactList;
   714         return m_contactList;
   744         if (wake && (m_flags & e_awakeFlag) == 0)
   750         if (m_flags & e_awakeFlag)
   753                 m_torque += 
b2Cross(point - m_sweep.c, force);
   764         if (wake && (m_flags & e_awakeFlag) == 0)
   770         if (m_flags & e_awakeFlag)
   783         if (wake && (m_flags & e_awakeFlag) == 0)
   789         if (m_flags & e_awakeFlag)
   802         if (wake && (m_flags & e_awakeFlag) == 0)
   808         if (m_flags & e_awakeFlag)
   810                 m_linearVelocity += m_invMass * impulse;
   811                 m_angularVelocity += m_invI * 
b2Cross(point - m_sweep.c, impulse);
   822         if (wake && (m_flags & e_awakeFlag) == 0)
   828         if (m_flags & e_awakeFlag)
   830                 m_angularVelocity += m_invI * impulse;
   836         m_xf.q.Set(m_sweep.a);
   837         m_xf.p = m_sweep.c - 
b2Mul(m_xf.q, m_sweep.localCenter);
   843         m_sweep.Advance(alpha);
   844         m_sweep.c = m_sweep.c0;
   845         m_sweep.a = m_sweep.a0;
   846         m_xf.q.Set(m_sweep.a);
   847         m_xf.p = m_sweep.c - 
b2Mul(m_xf.q, m_sweep.localCenter);
 b2BodyDef()
This constructor sets the body definition default values. 
This is an internal class. 
float32 b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors. 
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
float32 angularVelocity
The angular velocity of the body. 
bool fixedRotation
Should this body be prevented from rotating? Useful for characters. 
bool IsBullet() const 
Is this body treated like a bullet for continuous collision detection? 
GLenum GLenum GLenum GLenum GLenum scale
void SetUserData(void *data)
Set the user data. Use this to store your application specific data. 
void ApplyForceToCenter(const b2Vec2 &force, bool wake)
GLclampf GLclampf GLclampf alpha
void SetAngularVelocity(float32 omega)
float32 I
The rotational inertia of the shape about the local origin. 
GLubyte GLubyte GLubyte GLubyte w
void SetAngularDamping(float32 angularDamping)
Set the angular damping of the body. 
void ApplyForce(const b2Vec2 &force, const b2Vec2 &point, bool wake)
b2ContactEdge * GetContactList()
b2ContactEdge * m_contactList
float32 GetInertia() const 
void ApplyTorque(float32 torque, bool wake)
float32 GetGravityScale() const 
Get the gravity scale of the body. 
float32 GetAngularDamping() const 
Get the angular damping of the body. 
void SetSleepingAllowed(bool flag)
b2Vec2 GetWorldPoint(const b2Vec2 &localPoint) const 
void SetLinearDamping(float32 linearDamping)
Set the linear damping of the body. 
b2Vec2 center
The position of the shape's centroid relative to the shape's origin. 
b2JointEdge * GetJointList()
Get the list of all joints attached to this body. 
float32 GetAngularVelocity() const 
float32 b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar. 
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? 
float32 angle
The world angle of the body in radians. 
bool active
Does this body start out active? 
A rigid body. These are created via b2World::CreateBody. 
float32 GetLinearDamping() const 
Get the linear damping of the body. 
float32 mass
The mass of the shape, usually in kilograms. 
void SetLinearVelocity(const b2Vec2 &v)
b2Vec2 GetWorldVector(const b2Vec2 &localVector) const 
float32 gravityScale
Scale the gravity applied to this body. 
GLint GLenum GLsizei GLint GLsizei const GLvoid * data
b2Body * GetNext()
Get the next body in the world's body list. 
b2Vec2 GetLinearVelocityFromWorldPoint(const b2Vec2 &worldPoint) const 
bool awake
Is this body initially awake or sleeping? 
void SynchronizeTransform()
bool IsActive() const 
Get the active state of the body. 
b2Vec2 b2MulT(const b2Mat22 &A, const b2Vec2 &v)
const b2Vec2 & GetLocalCenter() const 
Get the local position of the center of mass. 
void SetGravityScale(float32 scale)
Set the gravity scale of the body. 
void GetMassData(b2MassData *data) const 
b2Vec2 GetLinearVelocityFromLocalPoint(const b2Vec2 &localPoint) const 
b2Vec2 GetLocalPoint(const b2Vec2 &worldPoint) const 
bool IsFixedRotation() const 
Does this body have fixed rotation? 
b2Vec2 GetLocalVector(const b2Vec2 &worldVector) const 
b2BodyType GetType() const 
Get the type of this body. 
const b2Vec2 & GetLinearVelocity() const 
const b2Vec2 & GetWorldCenter() const 
Get the world position of the center of mass. 
const b2Vec2 & GetPosition() const 
float32 m_angularVelocity
b2Fixture * GetFixtureList()
Get the list of all fixtures attached to this body. 
void * GetUserData() const 
Get the user data pointer that was provided in the body definition. 
void ApplyLinearImpulse(const b2Vec2 &impulse, const b2Vec2 &point, bool wake)
const b2Transform & GetTransform() const 
GLuint GLuint GLsizei GLenum type
void Set(float32 x_, float32 y_)
Set this vector to some specified coordinates. 
This holds the mass data computed for a shape. 
void ApplyAngularImpulse(float32 impulse, bool wake)
bool IsSleepingAllowed() const 
Is this body allowed to sleep. 
void * userData
Use this to store application specific body data. 
b2World * GetWorld()
Get the parent world of this body. 
b2Fixture * m_fixtureList
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f