256 if (edge->
other == bodyA)
350 if (collideConnected ==
false)
355 if (edge->
other == bodyA)
402 b->m_flags &= ~
b2Body::e_islandFlag;
410 j->m_islandFlag =
false;
423 if (seed->IsAwake() ==
false || seed->IsActive() ==
false)
436 int32 stackCount = 0;
437 stack[stackCount++] = seed;
441 while (stackCount > 0)
444 b2Body* b = stack[--stackCount];
479 if (sensorA || sensorB)
487 b2Body* other = ce->other;
496 stack[stackCount++] = other;
503 if (je->joint->m_islandFlag ==
true)
508 b2Body* other = je->other;
516 island.
Add(je->joint);
517 je->joint->m_islandFlag =
true;
525 stack[stackCount++] = other;
567 b->SynchronizeFixtures();
585 b->m_flags &= ~
b2Body::e_islandFlag;
608 if (c->IsEnabled() ==
false)
647 if (activeA ==
false && activeB ==
false)
656 if (collideA ==
false && collideB ==
false)
678 int32 indexA = c->GetChildIndexA();
679 int32 indexB = c->GetChildIndexB();
696 alpha =
b2Min(alpha0 + (1.0
f - alpha0) * beta, 1.0
f);
707 if (alpha < minAlpha)
715 if (minContact == NULL || 1.0
f - 10.0
f *
b2_epsilon < minAlpha)
758 island.
Add(minContact);
765 b2Body* bodies[2] = {bA, bB};
766 for (
int32 i = 0; i < 2; ++i)
792 b2Body* other = ce->other;
802 if (sensorA || sensorB)
857 subStep.
dt = (1.0f - minAlpha) * step.
dt;
969 body->m_force.SetZero();
970 body->m_torque = 0.0f;
979 return callback->ReportFixture(proxy->
fixture);
998 void* userData = broadPhase->GetUserData(proxyId);
1003 bool hit = fixture->
RayCast(&output, input, index);
1008 b2Vec2 point = (1.0f - fraction) * input.
p1 + fraction * input.
p2;
1009 return callback->ReportFixture(fixture, point, output.
normal, fraction);
1063 for (
int32 i = 1; i < count; ++i)
1080 for (
int32 i = 0; i < vertexCount; ++i)
1149 for (
b2Fixture*
f = b->GetFixtureList();
f;
f =
f->GetNext())
1151 if (b->IsActive() ==
false)
1163 else if (b->IsAwake() ==
false)
1205 if (b->IsActive() ==
false)
1210 for (
b2Fixture*
f = b->GetFixtureList();
f;
f =
f->GetNext())
1212 for (
int32 i = 0; i <
f->m_proxyCount; ++i)
1233 xf.
p = b->GetWorldCenter();
1262 if ((
m_flags & e_locked) == e_locked)
1269 b->m_xf.p -= newOrigin;
1270 b->m_sweep.c0 -= newOrigin;
1271 b->m_sweep.c -= newOrigin;
1276 j->ShiftOrigin(newOrigin);
1290 b2Log(
"m_world->SetGravity(g);\n");
1292 b2Log(
"b2Body** bodies = (b2Body**)b2Alloc(%d * sizeof(b2Body*));\n",
m_bodyCount);
1293 b2Log(
"b2Joint** joints = (b2Joint**)b2Alloc(%d * sizeof(b2Joint*));\n",
m_jointCount);
1297 b->m_islandIndex = i;
1335 b2Log(
"b2Free(joints);\n");
1336 b2Log(
"b2Free(bodies);\n");
1337 b2Log(
"joints = NULL;\n");
1338 b2Log(
"bodies = NULL;\n");
This is an internal class.
#define b2_maxSubSteps
Maximum number of sub-steps per contact in continuous physics simulation.
virtual void DrawSegment(const b2Vec2 &p1, const b2Vec2 &p2, const b2Color &color)=0
Draw a line segment.
virtual void DrawTransform(const b2Transform &xf)=0
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
void Advance(float32 alpha)
b2Vec2 * m_vertices
The vertices. Owned by this class.
void Step(float32 timeStep, int32 velocityIterations, int32 positionIterations)
void SynchronizeFixtures()
void Set(const b2Shape *shape, int32 index)
void b2Log(const char *string,...)
Logging function.
bool IsBullet() const
Is this body treated like a bullet for continuous collision detection?
int32 GetProxyCount() const
Get the number of broad-phase proxies.
static void Destroy(b2Joint *joint, b2BlockAllocator *allocator)
b2ContactManager m_contactManager
b2Shape::Type GetType() const
int32 GetTreeBalance() const
Get the balance of the embedded tree.
b2Vec2 lowerBound
the lower vertex
void SetAllowSleeping(bool flag)
Enable/disable sleep.
void b2TimeOfImpact(b2TOIOutput *output, const b2TOIInput *input)
Joint definitions are used to construct joints.
b2Body * GetBodyA()
Get the first body attached to this joint.
void DrawShape(b2Fixture *shape, const b2Transform &xf, const b2Color &color)
bool RayCast(b2RayCastOutput *output, const b2RayCastInput &input, int32 childIndex) const
b2Vec2 GetGroundAnchorB() const
Get the second ground anchor.
virtual void DrawSolidCircle(const b2Vec2 ¢er, float32 radius, const b2Vec2 &axis, const b2Color &color)=0
Draw a solid circle.
float32 GetMilliseconds() const
Get the time since construction or the last reset.
b2ContactEdge * GetContactList()
float32 GetTreeQuality() const
Get the quality metric of the embedded tree.
b2JointType GetType() const
Get the type of the concrete joint.
b2JointEdge * prev
the previous joint edge in the body's joint list
b2ContactEdge * m_contactList
const b2BroadPhase * broadPhase
float32 GetTreeQuality() const
b2World(const b2Vec2 &gravity)
void Free(void *p, int32 size)
Free memory. This will use b2Free if the size is larger than b2_maxBlockSize.
b2Joint * GetNext()
Get the next joint the world joint list.
This is an internal structure.
This proxy is used internally to connect fixtures to the broad-phase.
void SetDebugDraw(b2Draw *debugDraw)
void DestroyJoint(b2Joint *joint)
const b2BroadPhase * broadPhase
b2Body * other
provides quick access to the other body attached.
void ShiftOrigin(const b2Vec2 &newOrigin)
void SolveTOI(const b2TimeStep &subStep, int32 toiIndexA, int32 toiIndexB)
void Query(T *callback, const b2AABB &aabb) const
virtual void SayGoodbye(b2Joint *joint)=0
int32 GetProxyCount() const
Get the number of proxies.
int32 GetTreeBalance() const
Get the balance of the dynamic tree.
b2Body * GetBodyB()
Get the second body attached to this joint.
Color for debug drawing. Each value has the range [0,1].
virtual void DrawPolygon(const b2Vec2 *vertices, int32 vertexCount, const b2Color &color)=0
Draw a closed polygon provided in CCW order.
void Solve(const b2TimeStep &step)
b2JointEdge * m_jointList
void SolveTOI(const b2TimeStep &step)
draw center of mass frame
A rigid body. These are created via b2World::CreateBody.
void * Allocate(int32 size)
Allocate memory. This will use b2Alloc if the size is larger than b2_maxBlockSize.
void QueryAABB(b2QueryCallback *callback, const b2AABB &aabb) const
virtual b2Vec2 GetAnchorA() const =0
Get the anchor point on bodyA in world coordinates.
Profiling data. Times are in milliseconds.
virtual void DrawSolidPolygon(const b2Vec2 *vertices, int32 vertexCount, const b2Color &color)=0
Draw a solid closed polygon provided in CCW order.
b2Joint * CreateJoint(const b2JointDef *def)
void RayCast(b2RayCastCallback *callback, const b2Vec2 &point1, const b2Vec2 &point2) const
b2QueryCallback * callback
void * Allocate(int32 size)
bool collideConnected
Set this flag to true if the attached bodies should collide.
draw axis aligned bounding boxes
~b2World()
Destruct the world. All physics entities are destroyed and all heap memory is released.
void RayCast(T *callback, const b2RayCastInput &input) const
b2Body * GetNext()
Get the next body in the world's body list.
void DrawJoint(b2Joint *joint)
b2Vec2 m_vertices[b2_maxPolygonVertices]
void Destroy(b2BlockAllocator *allocator)
uint32 GetFlags() const
Get the drawing flags.
#define b2_maxPolygonVertices
b2RayCastCallback * callback
void ShiftOrigin(const b2Vec2 &newOrigin)
void SynchronizeTransform()
void SetContactListener(b2ContactListener *listener)
bool IsActive() const
Get the active state of the body.
int32 GetTreeHeight() const
Get the height of the embedded tree.
b2StackAllocator m_stackAllocator
void DrawDebugData()
Call this to draw shapes and other debug draw data. This is intentionally non-const.
const b2AABB & GetFatAABB(int32 proxyId) const
Get the fat AABB for a proxy.
virtual void DrawCircle(const b2Vec2 ¢er, float32 radius, const b2Color &color)=0
Draw a circle.
b2BodyType GetType() const
Get the type of this body.
An axis aligned bounding box.
virtual b2Vec2 GetAnchorB() const =0
Get the anchor point on bodyB in world coordinates.
b2DestructionListener * m_destructionListener
void SetDestructionListener(b2DestructionListener *listener)
void Solve(b2Profile *profile, const b2TimeStep &step, const b2Vec2 &gravity, bool allowSleep)
b2Vec2 m_vertex1
These are the edge vertices.
void DestroyBody(b2Body *body)
void DestroyProxies(b2BroadPhase *broadPhase)
#define b2_maxTOIContacts
Maximum number of contacts to be handled to solve a TOI impact.
b2BlockAllocator m_blockAllocator
int32 m_count
The vertex count.
const b2Transform & GetTransform() const
float32 RayCastCallback(const b2RayCastInput &input, int32 proxyId)
bool QueryCallback(int32 proxyId)
b2Body * bodyA
The first attached body.
static b2Joint * Create(const b2JointDef *def, b2BlockAllocator *allocator)
b2Vec2 GetGroundAnchorA() const
Get the first ground anchor.
void Set(float32 x_, float32 y_)
Set this vector to some specified coordinates.
int32 GetTreeHeight() const
Get the height of the dynamic tree.
void SetContactFilter(b2ContactFilter *filter)
b2Body * CreateBody(const b2BodyDef *def)
b2Body * bodyB
The second attached body.
b2JointEdge * next
the next joint edge in the body's joint list
b2Vec2 upperBound
the upper vertex
b2Fixture * m_fixtureList
bool IsLocked() const
Is the world locked (in the middle of a time step).