Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 #include <Box2D/Collision/b2Distance.h>
00020 #include <Box2D/Dynamics/b2Island.h>
00021 #include <Box2D/Dynamics/b2Body.h>
00022 #include <Box2D/Dynamics/b2Fixture.h>
00023 #include <Box2D/Dynamics/b2World.h>
00024 #include <Box2D/Dynamics/Contacts/b2Contact.h>
00025 #include <Box2D/Dynamics/Contacts/b2ContactSolver.h>
00026 #include <Box2D/Dynamics/Joints/b2Joint.h>
00027 #include <Box2D/Common/b2StackAllocator.h>
00028 #include <Box2D/Common/b2Timer.h>
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148 b2Island::b2Island(
00149 int32 bodyCapacity,
00150 int32 contactCapacity,
00151 int32 jointCapacity,
00152 b2StackAllocator* allocator,
00153 b2ContactListener* listener)
00154 {
00155 m_bodyCapacity = bodyCapacity;
00156 m_contactCapacity = contactCapacity;
00157 m_jointCapacity = jointCapacity;
00158 m_bodyCount = 0;
00159 m_contactCount = 0;
00160 m_jointCount = 0;
00161
00162 m_allocator = allocator;
00163 m_listener = listener;
00164
00165 m_bodies = (b2Body**)m_allocator->Allocate(bodyCapacity * sizeof(b2Body*));
00166 m_contacts = (b2Contact**)m_allocator->Allocate(contactCapacity * sizeof(b2Contact*));
00167 m_joints = (b2Joint**)m_allocator->Allocate(jointCapacity * sizeof(b2Joint*));
00168
00169 m_velocities = (b2Velocity*)m_allocator->Allocate(m_bodyCapacity * sizeof(b2Velocity));
00170 m_positions = (b2Position*)m_allocator->Allocate(m_bodyCapacity * sizeof(b2Position));
00171 }
00172
00173 b2Island::~b2Island()
00174 {
00175
00176 m_allocator->Free(m_positions);
00177 m_allocator->Free(m_velocities);
00178 m_allocator->Free(m_joints);
00179 m_allocator->Free(m_contacts);
00180 m_allocator->Free(m_bodies);
00181 }
00182
00183 void b2Island::Solve(b2Profile* profile, const b2TimeStep& step, const b2Vec2& gravity, bool allowSleep)
00184 {
00185 b2Timer timer;
00186
00187 float32 h = step.dt;
00188
00189
00190 for (int32 i = 0; i < m_bodyCount; ++i)
00191 {
00192 b2Body* b = m_bodies[i];
00193
00194 b2Vec2 c = b->m_sweep.c;
00195 float32 a = b->m_sweep.a;
00196 b2Vec2 v = b->m_linearVelocity;
00197 float32 w = b->m_angularVelocity;
00198
00199
00200 b->m_sweep.c0 = b->m_sweep.c;
00201 b->m_sweep.a0 = b->m_sweep.a;
00202
00203 if (b->m_type == b2_dynamicBody)
00204 {
00205
00206 v += h * (b->m_gravityScale * gravity + b->m_invMass * b->m_force);
00207 w += h * b->m_invI * b->m_torque;
00208
00209
00210
00211
00212
00213
00214
00215
00216 v *= 1.0f / (1.0f + h * b->m_linearDamping);
00217 w *= 1.0f / (1.0f + h * b->m_angularDamping);
00218 }
00219
00220 m_positions[i].c = c;
00221 m_positions[i].a = a;
00222 m_velocities[i].v = v;
00223 m_velocities[i].w = w;
00224 }
00225
00226 timer.Reset();
00227
00228
00229 b2SolverData solverData;
00230 solverData.step = step;
00231 solverData.positions = m_positions;
00232 solverData.velocities = m_velocities;
00233
00234
00235 b2ContactSolverDef contactSolverDef;
00236 contactSolverDef.step = step;
00237 contactSolverDef.contacts = m_contacts;
00238 contactSolverDef.count = m_contactCount;
00239 contactSolverDef.positions = m_positions;
00240 contactSolverDef.velocities = m_velocities;
00241 contactSolverDef.allocator = m_allocator;
00242
00243 b2ContactSolver contactSolver(&contactSolverDef);
00244 contactSolver.InitializeVelocityConstraints();
00245
00246 if (step.warmStarting)
00247 {
00248 contactSolver.WarmStart();
00249 }
00250
00251 for (int32 i = 0; i < m_jointCount; ++i)
00252 {
00253 m_joints[i]->InitVelocityConstraints(solverData);
00254 }
00255
00256 profile->solveInit = timer.GetMilliseconds();
00257
00258
00259 timer.Reset();
00260 for (int32 i = 0; i < step.velocityIterations; ++i)
00261 {
00262 for (int32 j = 0; j < m_jointCount; ++j)
00263 {
00264 m_joints[j]->SolveVelocityConstraints(solverData);
00265 }
00266
00267 contactSolver.SolveVelocityConstraints();
00268 }
00269
00270
00271 contactSolver.StoreImpulses();
00272 profile->solveVelocity = timer.GetMilliseconds();
00273
00274
00275 for (int32 i = 0; i < m_bodyCount; ++i)
00276 {
00277 b2Vec2 c = m_positions[i].c;
00278 float32 a = m_positions[i].a;
00279 b2Vec2 v = m_velocities[i].v;
00280 float32 w = m_velocities[i].w;
00281
00282
00283 b2Vec2 translation = h * v;
00284 if (b2Dot(translation, translation) > b2_maxTranslationSquared)
00285 {
00286 float32 ratio = b2_maxTranslation / translation.Length();
00287 v *= ratio;
00288 }
00289
00290 float32 rotation = h * w;
00291 if (rotation * rotation > b2_maxRotationSquared)
00292 {
00293 float32 ratio = b2_maxRotation / b2Abs(rotation);
00294 w *= ratio;
00295 }
00296
00297
00298 c += h * v;
00299 a += h * w;
00300
00301 m_positions[i].c = c;
00302 m_positions[i].a = a;
00303 m_velocities[i].v = v;
00304 m_velocities[i].w = w;
00305 }
00306
00307
00308 timer.Reset();
00309 bool positionSolved = false;
00310 for (int32 i = 0; i < step.positionIterations; ++i)
00311 {
00312 bool contactsOkay = contactSolver.SolvePositionConstraints();
00313
00314 bool jointsOkay = true;
00315 for (int32 i = 0; i < m_jointCount; ++i)
00316 {
00317 bool jointOkay = m_joints[i]->SolvePositionConstraints(solverData);
00318 jointsOkay = jointsOkay && jointOkay;
00319 }
00320
00321 if (contactsOkay && jointsOkay)
00322 {
00323
00324 positionSolved = true;
00325 break;
00326 }
00327 }
00328
00329
00330 for (int32 i = 0; i < m_bodyCount; ++i)
00331 {
00332 b2Body* body = m_bodies[i];
00333 body->m_sweep.c = m_positions[i].c;
00334 body->m_sweep.a = m_positions[i].a;
00335 body->m_linearVelocity = m_velocities[i].v;
00336 body->m_angularVelocity = m_velocities[i].w;
00337 body->SynchronizeTransform();
00338 }
00339
00340 profile->solvePosition = timer.GetMilliseconds();
00341
00342 Report(contactSolver.m_velocityConstraints);
00343
00344 if (allowSleep)
00345 {
00346 float32 minSleepTime = b2_maxFloat;
00347
00348 const float32 linTolSqr = b2_linearSleepTolerance * b2_linearSleepTolerance;
00349 const float32 angTolSqr = b2_angularSleepTolerance * b2_angularSleepTolerance;
00350
00351 for (int32 i = 0; i < m_bodyCount; ++i)
00352 {
00353 b2Body* b = m_bodies[i];
00354 if (b->GetType() == b2_staticBody)
00355 {
00356 continue;
00357 }
00358
00359 if ((b->m_flags & b2Body::e_autoSleepFlag) == 0 ||
00360 b->m_angularVelocity * b->m_angularVelocity > angTolSqr ||
00361 b2Dot(b->m_linearVelocity, b->m_linearVelocity) > linTolSqr)
00362 {
00363 b->m_sleepTime = 0.0f;
00364 minSleepTime = 0.0f;
00365 }
00366 else
00367 {
00368 b->m_sleepTime += h;
00369 minSleepTime = b2Min(minSleepTime, b->m_sleepTime);
00370 }
00371 }
00372
00373 if (minSleepTime >= b2_timeToSleep && positionSolved)
00374 {
00375 for (int32 i = 0; i < m_bodyCount; ++i)
00376 {
00377 b2Body* b = m_bodies[i];
00378 b->SetAwake(false);
00379 }
00380 }
00381 }
00382 }
00383
00384 void b2Island::SolveTOI(const b2TimeStep& subStep, int32 toiIndexA, int32 toiIndexB)
00385 {
00386 b2Assert(toiIndexA < m_bodyCount);
00387 b2Assert(toiIndexB < m_bodyCount);
00388
00389
00390 for (int32 i = 0; i < m_bodyCount; ++i)
00391 {
00392 b2Body* b = m_bodies[i];
00393 m_positions[i].c = b->m_sweep.c;
00394 m_positions[i].a = b->m_sweep.a;
00395 m_velocities[i].v = b->m_linearVelocity;
00396 m_velocities[i].w = b->m_angularVelocity;
00397 }
00398
00399 b2ContactSolverDef contactSolverDef;
00400 contactSolverDef.contacts = m_contacts;
00401 contactSolverDef.count = m_contactCount;
00402 contactSolverDef.allocator = m_allocator;
00403 contactSolverDef.step = subStep;
00404 contactSolverDef.positions = m_positions;
00405 contactSolverDef.velocities = m_velocities;
00406 b2ContactSolver contactSolver(&contactSolverDef);
00407
00408
00409 for (int32 i = 0; i < subStep.positionIterations; ++i)
00410 {
00411 bool contactsOkay = contactSolver.SolveTOIPositionConstraints(toiIndexA, toiIndexB);
00412 if (contactsOkay)
00413 {
00414 break;
00415 }
00416 }
00417
00418 #if 0
00419
00420 for (int32 i = 0; i < m_contactCount; ++i)
00421 {
00422 b2Contact* c = m_contacts[i];
00423 b2Fixture* fA = c->GetFixtureA();
00424 b2Fixture* fB = c->GetFixtureB();
00425
00426 b2Body* bA = fA->GetBody();
00427 b2Body* bB = fB->GetBody();
00428
00429 int32 indexA = c->GetChildIndexA();
00430 int32 indexB = c->GetChildIndexB();
00431
00432 b2DistanceInput input;
00433 input.proxyA.Set(fA->GetShape(), indexA);
00434 input.proxyB.Set(fB->GetShape(), indexB);
00435 input.transformA = bA->GetTransform();
00436 input.transformB = bB->GetTransform();
00437 input.useRadii = false;
00438
00439 b2DistanceOutput output;
00440 b2SimplexCache cache;
00441 cache.count = 0;
00442 b2Distance(&output, &cache, &input);
00443
00444 if (output.distance == 0 || cache.count == 3)
00445 {
00446 cache.count += 0;
00447 }
00448 }
00449 #endif
00450
00451
00452 m_bodies[toiIndexA]->m_sweep.c0 = m_positions[toiIndexA].c;
00453 m_bodies[toiIndexA]->m_sweep.a0 = m_positions[toiIndexA].a;
00454 m_bodies[toiIndexB]->m_sweep.c0 = m_positions[toiIndexB].c;
00455 m_bodies[toiIndexB]->m_sweep.a0 = m_positions[toiIndexB].a;
00456
00457
00458
00459 contactSolver.InitializeVelocityConstraints();
00460
00461
00462 for (int32 i = 0; i < subStep.velocityIterations; ++i)
00463 {
00464 contactSolver.SolveVelocityConstraints();
00465 }
00466
00467
00468
00469
00470 float32 h = subStep.dt;
00471
00472
00473 for (int32 i = 0; i < m_bodyCount; ++i)
00474 {
00475 b2Vec2 c = m_positions[i].c;
00476 float32 a = m_positions[i].a;
00477 b2Vec2 v = m_velocities[i].v;
00478 float32 w = m_velocities[i].w;
00479
00480
00481 b2Vec2 translation = h * v;
00482 if (b2Dot(translation, translation) > b2_maxTranslationSquared)
00483 {
00484 float32 ratio = b2_maxTranslation / translation.Length();
00485 v *= ratio;
00486 }
00487
00488 float32 rotation = h * w;
00489 if (rotation * rotation > b2_maxRotationSquared)
00490 {
00491 float32 ratio = b2_maxRotation / b2Abs(rotation);
00492 w *= ratio;
00493 }
00494
00495
00496 c += h * v;
00497 a += h * w;
00498
00499 m_positions[i].c = c;
00500 m_positions[i].a = a;
00501 m_velocities[i].v = v;
00502 m_velocities[i].w = w;
00503
00504
00505 b2Body* body = m_bodies[i];
00506 body->m_sweep.c = c;
00507 body->m_sweep.a = a;
00508 body->m_linearVelocity = v;
00509 body->m_angularVelocity = w;
00510 body->SynchronizeTransform();
00511 }
00512
00513 Report(contactSolver.m_velocityConstraints);
00514 }
00515
00516 void b2Island::Report(const b2ContactVelocityConstraint* constraints)
00517 {
00518 if (m_listener == NULL)
00519 {
00520 return;
00521 }
00522
00523 for (int32 i = 0; i < m_contactCount; ++i)
00524 {
00525 b2Contact* c = m_contacts[i];
00526
00527 const b2ContactVelocityConstraint* vc = constraints + i;
00528
00529 b2ContactImpulse impulse;
00530 impulse.count = vc->pointCount;
00531 for (int32 j = 0; j < vc->pointCount; ++j)
00532 {
00533 impulse.normalImpulses[j] = vc->points[j].normalImpulse;
00534 impulse.tangentImpulses[j] = vc->points[j].tangentImpulse;
00535 }
00536
00537 m_listener->PostSolve(c, &impulse);
00538 }
00539 }