b2ContactSolver.cpp
Go to the documentation of this file.
00001 /*
00002 * Copyright (c) 2006-2011 Erin Catto http://www.box2d.org
00003 *
00004 * This software is provided 'as-is', without any express or implied
00005 * warranty.  In no event will the authors be held liable for any damages
00006 * arising from the use of this software.
00007 * Permission is granted to anyone to use this software for any purpose,
00008 * including commercial applications, and to alter it and redistribute it
00009 * freely, subject to the following restrictions:
00010 * 1. The origin of this software must not be misrepresented; you must not
00011 * claim that you wrote the original software. If you use this software
00012 * in a product, an acknowledgment in the product documentation would be
00013 * appreciated but is not required.
00014 * 2. Altered source versions must be plainly marked as such, and must not be
00015 * misrepresented as being the original software.
00016 * 3. This notice may not be removed or altered from any source distribution.
00017 */
00018 
00019 #include <Box2D/Dynamics/Contacts/b2ContactSolver.h>
00020 
00021 #include <Box2D/Dynamics/Contacts/b2Contact.h>
00022 #include <Box2D/Dynamics/b2Body.h>
00023 #include <Box2D/Dynamics/b2Fixture.h>
00024 #include <Box2D/Dynamics/b2World.h>
00025 #include <Box2D/Common/b2StackAllocator.h>
00026 
00027 #define B2_DEBUG_SOLVER 0
00028 
00029 bool g_blockSolve = true;
00030 
00031 struct b2ContactPositionConstraint
00032 {
00033         b2Vec2 localPoints[b2_maxManifoldPoints];
00034         b2Vec2 localNormal;
00035         b2Vec2 localPoint;
00036         int32 indexA;
00037         int32 indexB;
00038         float32 invMassA, invMassB;
00039         b2Vec2 localCenterA, localCenterB;
00040         float32 invIA, invIB;
00041         b2Manifold::Type type;
00042         float32 radiusA, radiusB;
00043         int32 pointCount;
00044 };
00045 
00046 b2ContactSolver::b2ContactSolver(b2ContactSolverDef* def)
00047 {
00048         m_step = def->step;
00049         m_allocator = def->allocator;
00050         m_count = def->count;
00051         m_positionConstraints = (b2ContactPositionConstraint*)m_allocator->Allocate(m_count * sizeof(b2ContactPositionConstraint));
00052         m_velocityConstraints = (b2ContactVelocityConstraint*)m_allocator->Allocate(m_count * sizeof(b2ContactVelocityConstraint));
00053         m_positions = def->positions;
00054         m_velocities = def->velocities;
00055         m_contacts = def->contacts;
00056 
00057         // Initialize position independent portions of the constraints.
00058         for (int32 i = 0; i < m_count; ++i)
00059         {
00060                 b2Contact* contact = m_contacts[i];
00061 
00062                 b2Fixture* fixtureA = contact->m_fixtureA;
00063                 b2Fixture* fixtureB = contact->m_fixtureB;
00064                 b2Shape* shapeA = fixtureA->GetShape();
00065                 b2Shape* shapeB = fixtureB->GetShape();
00066                 float32 radiusA = shapeA->m_radius;
00067                 float32 radiusB = shapeB->m_radius;
00068                 b2Body* bodyA = fixtureA->GetBody();
00069                 b2Body* bodyB = fixtureB->GetBody();
00070                 b2Manifold* manifold = contact->GetManifold();
00071 
00072                 int32 pointCount = manifold->pointCount;
00073                 b2Assert(pointCount > 0);
00074 
00075                 b2ContactVelocityConstraint* vc = m_velocityConstraints + i;
00076                 vc->friction = contact->m_friction;
00077                 vc->restitution = contact->m_restitution;
00078                 vc->tangentSpeed = contact->m_tangentSpeed;
00079                 vc->indexA = bodyA->m_islandIndex;
00080                 vc->indexB = bodyB->m_islandIndex;
00081                 vc->invMassA = bodyA->m_invMass;
00082                 vc->invMassB = bodyB->m_invMass;
00083                 vc->invIA = bodyA->m_invI;
00084                 vc->invIB = bodyB->m_invI;
00085                 vc->contactIndex = i;
00086                 vc->pointCount = pointCount;
00087                 vc->K.SetZero();
00088                 vc->normalMass.SetZero();
00089 
00090                 b2ContactPositionConstraint* pc = m_positionConstraints + i;
00091                 pc->indexA = bodyA->m_islandIndex;
00092                 pc->indexB = bodyB->m_islandIndex;
00093                 pc->invMassA = bodyA->m_invMass;
00094                 pc->invMassB = bodyB->m_invMass;
00095                 pc->localCenterA = bodyA->m_sweep.localCenter;
00096                 pc->localCenterB = bodyB->m_sweep.localCenter;
00097                 pc->invIA = bodyA->m_invI;
00098                 pc->invIB = bodyB->m_invI;
00099                 pc->localNormal = manifold->localNormal;
00100                 pc->localPoint = manifold->localPoint;
00101                 pc->pointCount = pointCount;
00102                 pc->radiusA = radiusA;
00103                 pc->radiusB = radiusB;
00104                 pc->type = manifold->type;
00105 
00106                 for (int32 j = 0; j < pointCount; ++j)
00107                 {
00108                         b2ManifoldPoint* cp = manifold->points + j;
00109                         b2VelocityConstraintPoint* vcp = vc->points + j;
00110         
00111                         if (m_step.warmStarting)
00112                         {
00113                                 vcp->normalImpulse = m_step.dtRatio * cp->normalImpulse;
00114                                 vcp->tangentImpulse = m_step.dtRatio * cp->tangentImpulse;
00115                         }
00116                         else
00117                         {
00118                                 vcp->normalImpulse = 0.0f;
00119                                 vcp->tangentImpulse = 0.0f;
00120                         }
00121 
00122                         vcp->rA.SetZero();
00123                         vcp->rB.SetZero();
00124                         vcp->normalMass = 0.0f;
00125                         vcp->tangentMass = 0.0f;
00126                         vcp->velocityBias = 0.0f;
00127 
00128                         pc->localPoints[j] = cp->localPoint;
00129                 }
00130         }
00131 }
00132 
00133 b2ContactSolver::~b2ContactSolver()
00134 {
00135         m_allocator->Free(m_velocityConstraints);
00136         m_allocator->Free(m_positionConstraints);
00137 }
00138 
00139 // Initialize position dependent portions of the velocity constraints.
00140 void b2ContactSolver::InitializeVelocityConstraints()
00141 {
00142         for (int32 i = 0; i < m_count; ++i)
00143         {
00144                 b2ContactVelocityConstraint* vc = m_velocityConstraints + i;
00145                 b2ContactPositionConstraint* pc = m_positionConstraints + i;
00146 
00147                 float32 radiusA = pc->radiusA;
00148                 float32 radiusB = pc->radiusB;
00149                 b2Manifold* manifold = m_contacts[vc->contactIndex]->GetManifold();
00150 
00151                 int32 indexA = vc->indexA;
00152                 int32 indexB = vc->indexB;
00153 
00154                 float32 mA = vc->invMassA;
00155                 float32 mB = vc->invMassB;
00156                 float32 iA = vc->invIA;
00157                 float32 iB = vc->invIB;
00158                 b2Vec2 localCenterA = pc->localCenterA;
00159                 b2Vec2 localCenterB = pc->localCenterB;
00160 
00161                 b2Vec2 cA = m_positions[indexA].c;
00162                 float32 aA = m_positions[indexA].a;
00163                 b2Vec2 vA = m_velocities[indexA].v;
00164                 float32 wA = m_velocities[indexA].w;
00165 
00166                 b2Vec2 cB = m_positions[indexB].c;
00167                 float32 aB = m_positions[indexB].a;
00168                 b2Vec2 vB = m_velocities[indexB].v;
00169                 float32 wB = m_velocities[indexB].w;
00170 
00171                 b2Assert(manifold->pointCount > 0);
00172 
00173                 b2Transform xfA, xfB;
00174                 xfA.q.Set(aA);
00175                 xfB.q.Set(aB);
00176                 xfA.p = cA - b2Mul(xfA.q, localCenterA);
00177                 xfB.p = cB - b2Mul(xfB.q, localCenterB);
00178 
00179                 b2WorldManifold worldManifold;
00180                 worldManifold.Initialize(manifold, xfA, radiusA, xfB, radiusB);
00181 
00182                 vc->normal = worldManifold.normal;
00183 
00184                 int32 pointCount = vc->pointCount;
00185                 for (int32 j = 0; j < pointCount; ++j)
00186                 {
00187                         b2VelocityConstraintPoint* vcp = vc->points + j;
00188 
00189                         vcp->rA = worldManifold.points[j] - cA;
00190                         vcp->rB = worldManifold.points[j] - cB;
00191 
00192                         float32 rnA = b2Cross(vcp->rA, vc->normal);
00193                         float32 rnB = b2Cross(vcp->rB, vc->normal);
00194 
00195                         float32 kNormal = mA + mB + iA * rnA * rnA + iB * rnB * rnB;
00196 
00197                         vcp->normalMass = kNormal > 0.0f ? 1.0f / kNormal : 0.0f;
00198 
00199                         b2Vec2 tangent = b2Cross(vc->normal, 1.0f);
00200 
00201                         float32 rtA = b2Cross(vcp->rA, tangent);
00202                         float32 rtB = b2Cross(vcp->rB, tangent);
00203 
00204                         float32 kTangent = mA + mB + iA * rtA * rtA + iB * rtB * rtB;
00205 
00206                         vcp->tangentMass = kTangent > 0.0f ? 1.0f /  kTangent : 0.0f;
00207 
00208                         // Setup a velocity bias for restitution.
00209                         vcp->velocityBias = 0.0f;
00210                         float32 vRel = b2Dot(vc->normal, vB + b2Cross(wB, vcp->rB) - vA - b2Cross(wA, vcp->rA));
00211                         if (vRel < -b2_velocityThreshold)
00212                         {
00213                                 vcp->velocityBias = -vc->restitution * vRel;
00214                         }
00215                 }
00216 
00217                 // If we have two points, then prepare the block solver.
00218                 if (vc->pointCount == 2 && g_blockSolve)
00219                 {
00220                         b2VelocityConstraintPoint* vcp1 = vc->points + 0;
00221                         b2VelocityConstraintPoint* vcp2 = vc->points + 1;
00222 
00223                         float32 rn1A = b2Cross(vcp1->rA, vc->normal);
00224                         float32 rn1B = b2Cross(vcp1->rB, vc->normal);
00225                         float32 rn2A = b2Cross(vcp2->rA, vc->normal);
00226                         float32 rn2B = b2Cross(vcp2->rB, vc->normal);
00227 
00228                         float32 k11 = mA + mB + iA * rn1A * rn1A + iB * rn1B * rn1B;
00229                         float32 k22 = mA + mB + iA * rn2A * rn2A + iB * rn2B * rn2B;
00230                         float32 k12 = mA + mB + iA * rn1A * rn2A + iB * rn1B * rn2B;
00231 
00232                         // Ensure a reasonable condition number.
00233                         const float32 k_maxConditionNumber = 1000.0f;
00234                         if (k11 * k11 < k_maxConditionNumber * (k11 * k22 - k12 * k12))
00235                         {
00236                                 // K is safe to invert.
00237                                 vc->K.ex.Set(k11, k12);
00238                                 vc->K.ey.Set(k12, k22);
00239                                 vc->normalMass = vc->K.GetInverse();
00240                         }
00241                         else
00242                         {
00243                                 // The constraints are redundant, just use one.
00244                                 // TODO_ERIN use deepest?
00245                                 vc->pointCount = 1;
00246                         }
00247                 }
00248         }
00249 }
00250 
00251 void b2ContactSolver::WarmStart()
00252 {
00253         // Warm start.
00254         for (int32 i = 0; i < m_count; ++i)
00255         {
00256                 b2ContactVelocityConstraint* vc = m_velocityConstraints + i;
00257 
00258                 int32 indexA = vc->indexA;
00259                 int32 indexB = vc->indexB;
00260                 float32 mA = vc->invMassA;
00261                 float32 iA = vc->invIA;
00262                 float32 mB = vc->invMassB;
00263                 float32 iB = vc->invIB;
00264                 int32 pointCount = vc->pointCount;
00265 
00266                 b2Vec2 vA = m_velocities[indexA].v;
00267                 float32 wA = m_velocities[indexA].w;
00268                 b2Vec2 vB = m_velocities[indexB].v;
00269                 float32 wB = m_velocities[indexB].w;
00270 
00271                 b2Vec2 normal = vc->normal;
00272                 b2Vec2 tangent = b2Cross(normal, 1.0f);
00273 
00274                 for (int32 j = 0; j < pointCount; ++j)
00275                 {
00276                         b2VelocityConstraintPoint* vcp = vc->points + j;
00277                         b2Vec2 P = vcp->normalImpulse * normal + vcp->tangentImpulse * tangent;
00278                         wA -= iA * b2Cross(vcp->rA, P);
00279                         vA -= mA * P;
00280                         wB += iB * b2Cross(vcp->rB, P);
00281                         vB += mB * P;
00282                 }
00283 
00284                 m_velocities[indexA].v = vA;
00285                 m_velocities[indexA].w = wA;
00286                 m_velocities[indexB].v = vB;
00287                 m_velocities[indexB].w = wB;
00288         }
00289 }
00290 
00291 void b2ContactSolver::SolveVelocityConstraints()
00292 {
00293         for (int32 i = 0; i < m_count; ++i)
00294         {
00295                 b2ContactVelocityConstraint* vc = m_velocityConstraints + i;
00296 
00297                 int32 indexA = vc->indexA;
00298                 int32 indexB = vc->indexB;
00299                 float32 mA = vc->invMassA;
00300                 float32 iA = vc->invIA;
00301                 float32 mB = vc->invMassB;
00302                 float32 iB = vc->invIB;
00303                 int32 pointCount = vc->pointCount;
00304 
00305                 b2Vec2 vA = m_velocities[indexA].v;
00306                 float32 wA = m_velocities[indexA].w;
00307                 b2Vec2 vB = m_velocities[indexB].v;
00308                 float32 wB = m_velocities[indexB].w;
00309 
00310                 b2Vec2 normal = vc->normal;
00311                 b2Vec2 tangent = b2Cross(normal, 1.0f);
00312                 float32 friction = vc->friction;
00313 
00314                 b2Assert(pointCount == 1 || pointCount == 2);
00315 
00316                 // Solve tangent constraints first because non-penetration is more important
00317                 // than friction.
00318                 for (int32 j = 0; j < pointCount; ++j)
00319                 {
00320                         b2VelocityConstraintPoint* vcp = vc->points + j;
00321 
00322                         // Relative velocity at contact
00323                         b2Vec2 dv = vB + b2Cross(wB, vcp->rB) - vA - b2Cross(wA, vcp->rA);
00324 
00325                         // Compute tangent force
00326                         float32 vt = b2Dot(dv, tangent) - vc->tangentSpeed;
00327                         float32 lambda = vcp->tangentMass * (-vt);
00328 
00329                         // b2Clamp the accumulated force
00330                         float32 maxFriction = friction * vcp->normalImpulse;
00331                         float32 newImpulse = b2Clamp(vcp->tangentImpulse + lambda, -maxFriction, maxFriction);
00332                         lambda = newImpulse - vcp->tangentImpulse;
00333                         vcp->tangentImpulse = newImpulse;
00334 
00335                         // Apply contact impulse
00336                         b2Vec2 P = lambda * tangent;
00337 
00338                         vA -= mA * P;
00339                         wA -= iA * b2Cross(vcp->rA, P);
00340 
00341                         vB += mB * P;
00342                         wB += iB * b2Cross(vcp->rB, P);
00343                 }
00344 
00345                 // Solve normal constraints
00346                 if (pointCount == 1 || g_blockSolve == false)
00347                 {
00348                         for (int32 i = 0; i < pointCount; ++i)
00349                         {
00350                                 b2VelocityConstraintPoint* vcp = vc->points + i;
00351 
00352                                 // Relative velocity at contact
00353                                 b2Vec2 dv = vB + b2Cross(wB, vcp->rB) - vA - b2Cross(wA, vcp->rA);
00354 
00355                                 // Compute normal impulse
00356                                 float32 vn = b2Dot(dv, normal);
00357                                 float32 lambda = -vcp->normalMass * (vn - vcp->velocityBias);
00358 
00359                                 // b2Clamp the accumulated impulse
00360                                 float32 newImpulse = b2Max(vcp->normalImpulse + lambda, 0.0f);
00361                                 lambda = newImpulse - vcp->normalImpulse;
00362                                 vcp->normalImpulse = newImpulse;
00363 
00364                                 // Apply contact impulse
00365                                 b2Vec2 P = lambda * normal;
00366                                 vA -= mA * P;
00367                                 wA -= iA * b2Cross(vcp->rA, P);
00368 
00369                                 vB += mB * P;
00370                                 wB += iB * b2Cross(vcp->rB, P);
00371                         }
00372                 }
00373                 else
00374                 {
00375                         // Block solver developed in collaboration with Dirk Gregorius (back in 01/07 on Box2D_Lite).
00376                         // Build the mini LCP for this contact patch
00377                         //
00378                         // vn = A * x + b, vn >= 0, , vn >= 0, x >= 0 and vn_i * x_i = 0 with i = 1..2
00379                         //
00380                         // A = J * W * JT and J = ( -n, -r1 x n, n, r2 x n )
00381                         // b = vn0 - velocityBias
00382                         //
00383                         // The system is solved using the "Total enumeration method" (s. Murty). The complementary constraint vn_i * x_i
00384                         // implies that we must have in any solution either vn_i = 0 or x_i = 0. So for the 2D contact problem the cases
00385                         // vn1 = 0 and vn2 = 0, x1 = 0 and x2 = 0, x1 = 0 and vn2 = 0, x2 = 0 and vn1 = 0 need to be tested. The first valid
00386                         // solution that satisfies the problem is chosen.
00387                         // 
00388                         // In order to account of the accumulated impulse 'a' (because of the iterative nature of the solver which only requires
00389                         // that the accumulated impulse is clamped and not the incremental impulse) we change the impulse variable (x_i).
00390                         //
00391                         // Substitute:
00392                         // 
00393                         // x = a + d
00394                         // 
00395                         // a := old total impulse
00396                         // x := new total impulse
00397                         // d := incremental impulse 
00398                         //
00399                         // For the current iteration we extend the formula for the incremental impulse
00400                         // to compute the new total impulse:
00401                         //
00402                         // vn = A * d + b
00403                         //    = A * (x - a) + b
00404                         //    = A * x + b - A * a
00405                         //    = A * x + b'
00406                         // b' = b - A * a;
00407 
00408                         b2VelocityConstraintPoint* cp1 = vc->points + 0;
00409                         b2VelocityConstraintPoint* cp2 = vc->points + 1;
00410 
00411                         b2Vec2 a(cp1->normalImpulse, cp2->normalImpulse);
00412                         b2Assert(a.x >= 0.0f && a.y >= 0.0f);
00413 
00414                         // Relative velocity at contact
00415                         b2Vec2 dv1 = vB + b2Cross(wB, cp1->rB) - vA - b2Cross(wA, cp1->rA);
00416                         b2Vec2 dv2 = vB + b2Cross(wB, cp2->rB) - vA - b2Cross(wA, cp2->rA);
00417 
00418                         // Compute normal velocity
00419                         float32 vn1 = b2Dot(dv1, normal);
00420                         float32 vn2 = b2Dot(dv2, normal);
00421 
00422                         b2Vec2 b;
00423                         b.x = vn1 - cp1->velocityBias;
00424                         b.y = vn2 - cp2->velocityBias;
00425 
00426                         // Compute b'
00427                         b -= b2Mul(vc->K, a);
00428 
00429                         const float32 k_errorTol = 1e-3f;
00430                         B2_NOT_USED(k_errorTol);
00431 
00432                         for (;;)
00433                         {
00434                                 //
00435                                 // Case 1: vn = 0
00436                                 //
00437                                 // 0 = A * x + b'
00438                                 //
00439                                 // Solve for x:
00440                                 //
00441                                 // x = - inv(A) * b'
00442                                 //
00443                                 b2Vec2 x = - b2Mul(vc->normalMass, b);
00444 
00445                                 if (x.x >= 0.0f && x.y >= 0.0f)
00446                                 {
00447                                         // Get the incremental impulse
00448                                         b2Vec2 d = x - a;
00449 
00450                                         // Apply incremental impulse
00451                                         b2Vec2 P1 = d.x * normal;
00452                                         b2Vec2 P2 = d.y * normal;
00453                                         vA -= mA * (P1 + P2);
00454                                         wA -= iA * (b2Cross(cp1->rA, P1) + b2Cross(cp2->rA, P2));
00455 
00456                                         vB += mB * (P1 + P2);
00457                                         wB += iB * (b2Cross(cp1->rB, P1) + b2Cross(cp2->rB, P2));
00458 
00459                                         // Accumulate
00460                                         cp1->normalImpulse = x.x;
00461                                         cp2->normalImpulse = x.y;
00462 
00463 #if B2_DEBUG_SOLVER == 1
00464                                         // Postconditions
00465                                         dv1 = vB + b2Cross(wB, cp1->rB) - vA - b2Cross(wA, cp1->rA);
00466                                         dv2 = vB + b2Cross(wB, cp2->rB) - vA - b2Cross(wA, cp2->rA);
00467 
00468                                         // Compute normal velocity
00469                                         vn1 = b2Dot(dv1, normal);
00470                                         vn2 = b2Dot(dv2, normal);
00471 
00472                                         b2Assert(b2Abs(vn1 - cp1->velocityBias) < k_errorTol);
00473                                         b2Assert(b2Abs(vn2 - cp2->velocityBias) < k_errorTol);
00474 #endif
00475                                         break;
00476                                 }
00477 
00478                                 //
00479                                 // Case 2: vn1 = 0 and x2 = 0
00480                                 //
00481                                 //   0 = a11 * x1 + a12 * 0 + b1' 
00482                                 // vn2 = a21 * x1 + a22 * 0 + b2'
00483                                 //
00484                                 x.x = - cp1->normalMass * b.x;
00485                                 x.y = 0.0f;
00486                                 vn1 = 0.0f;
00487                                 vn2 = vc->K.ex.y * x.x + b.y;
00488 
00489                                 if (x.x >= 0.0f && vn2 >= 0.0f)
00490                                 {
00491                                         // Get the incremental impulse
00492                                         b2Vec2 d = x - a;
00493 
00494                                         // Apply incremental impulse
00495                                         b2Vec2 P1 = d.x * normal;
00496                                         b2Vec2 P2 = d.y * normal;
00497                                         vA -= mA * (P1 + P2);
00498                                         wA -= iA * (b2Cross(cp1->rA, P1) + b2Cross(cp2->rA, P2));
00499 
00500                                         vB += mB * (P1 + P2);
00501                                         wB += iB * (b2Cross(cp1->rB, P1) + b2Cross(cp2->rB, P2));
00502 
00503                                         // Accumulate
00504                                         cp1->normalImpulse = x.x;
00505                                         cp2->normalImpulse = x.y;
00506 
00507 #if B2_DEBUG_SOLVER == 1
00508                                         // Postconditions
00509                                         dv1 = vB + b2Cross(wB, cp1->rB) - vA - b2Cross(wA, cp1->rA);
00510 
00511                                         // Compute normal velocity
00512                                         vn1 = b2Dot(dv1, normal);
00513 
00514                                         b2Assert(b2Abs(vn1 - cp1->velocityBias) < k_errorTol);
00515 #endif
00516                                         break;
00517                                 }
00518 
00519 
00520                                 //
00521                                 // Case 3: vn2 = 0 and x1 = 0
00522                                 //
00523                                 // vn1 = a11 * 0 + a12 * x2 + b1' 
00524                                 //   0 = a21 * 0 + a22 * x2 + b2'
00525                                 //
00526                                 x.x = 0.0f;
00527                                 x.y = - cp2->normalMass * b.y;
00528                                 vn1 = vc->K.ey.x * x.y + b.x;
00529                                 vn2 = 0.0f;
00530 
00531                                 if (x.y >= 0.0f && vn1 >= 0.0f)
00532                                 {
00533                                         // Resubstitute for the incremental impulse
00534                                         b2Vec2 d = x - a;
00535 
00536                                         // Apply incremental impulse
00537                                         b2Vec2 P1 = d.x * normal;
00538                                         b2Vec2 P2 = d.y * normal;
00539                                         vA -= mA * (P1 + P2);
00540                                         wA -= iA * (b2Cross(cp1->rA, P1) + b2Cross(cp2->rA, P2));
00541 
00542                                         vB += mB * (P1 + P2);
00543                                         wB += iB * (b2Cross(cp1->rB, P1) + b2Cross(cp2->rB, P2));
00544 
00545                                         // Accumulate
00546                                         cp1->normalImpulse = x.x;
00547                                         cp2->normalImpulse = x.y;
00548 
00549 #if B2_DEBUG_SOLVER == 1
00550                                         // Postconditions
00551                                         dv2 = vB + b2Cross(wB, cp2->rB) - vA - b2Cross(wA, cp2->rA);
00552 
00553                                         // Compute normal velocity
00554                                         vn2 = b2Dot(dv2, normal);
00555 
00556                                         b2Assert(b2Abs(vn2 - cp2->velocityBias) < k_errorTol);
00557 #endif
00558                                         break;
00559                                 }
00560 
00561                                 //
00562                                 // Case 4: x1 = 0 and x2 = 0
00563                                 // 
00564                                 // vn1 = b1
00565                                 // vn2 = b2;
00566                                 x.x = 0.0f;
00567                                 x.y = 0.0f;
00568                                 vn1 = b.x;
00569                                 vn2 = b.y;
00570 
00571                                 if (vn1 >= 0.0f && vn2 >= 0.0f )
00572                                 {
00573                                         // Resubstitute for the incremental impulse
00574                                         b2Vec2 d = x - a;
00575 
00576                                         // Apply incremental impulse
00577                                         b2Vec2 P1 = d.x * normal;
00578                                         b2Vec2 P2 = d.y * normal;
00579                                         vA -= mA * (P1 + P2);
00580                                         wA -= iA * (b2Cross(cp1->rA, P1) + b2Cross(cp2->rA, P2));
00581 
00582                                         vB += mB * (P1 + P2);
00583                                         wB += iB * (b2Cross(cp1->rB, P1) + b2Cross(cp2->rB, P2));
00584 
00585                                         // Accumulate
00586                                         cp1->normalImpulse = x.x;
00587                                         cp2->normalImpulse = x.y;
00588 
00589                                         break;
00590                                 }
00591 
00592                                 // No solution, give up. This is hit sometimes, but it doesn't seem to matter.
00593                                 break;
00594                         }
00595                 }
00596 
00597                 m_velocities[indexA].v = vA;
00598                 m_velocities[indexA].w = wA;
00599                 m_velocities[indexB].v = vB;
00600                 m_velocities[indexB].w = wB;
00601         }
00602 }
00603 
00604 void b2ContactSolver::StoreImpulses()
00605 {
00606         for (int32 i = 0; i < m_count; ++i)
00607         {
00608                 b2ContactVelocityConstraint* vc = m_velocityConstraints + i;
00609                 b2Manifold* manifold = m_contacts[vc->contactIndex]->GetManifold();
00610 
00611                 for (int32 j = 0; j < vc->pointCount; ++j)
00612                 {
00613                         manifold->points[j].normalImpulse = vc->points[j].normalImpulse;
00614                         manifold->points[j].tangentImpulse = vc->points[j].tangentImpulse;
00615                 }
00616         }
00617 }
00618 
00619 struct b2PositionSolverManifold
00620 {
00621         void Initialize(b2ContactPositionConstraint* pc, const b2Transform& xfA, const b2Transform& xfB, int32 index)
00622         {
00623                 b2Assert(pc->pointCount > 0);
00624 
00625                 switch (pc->type)
00626                 {
00627                 case b2Manifold::e_circles:
00628                         {
00629                                 b2Vec2 pointA = b2Mul(xfA, pc->localPoint);
00630                                 b2Vec2 pointB = b2Mul(xfB, pc->localPoints[0]);
00631                                 normal = pointB - pointA;
00632                                 normal.Normalize();
00633                                 point = 0.5f * (pointA + pointB);
00634                                 separation = b2Dot(pointB - pointA, normal) - pc->radiusA - pc->radiusB;
00635                         }
00636                         break;
00637 
00638                 case b2Manifold::e_faceA:
00639                         {
00640                                 normal = b2Mul(xfA.q, pc->localNormal);
00641                                 b2Vec2 planePoint = b2Mul(xfA, pc->localPoint);
00642 
00643                                 b2Vec2 clipPoint = b2Mul(xfB, pc->localPoints[index]);
00644                                 separation = b2Dot(clipPoint - planePoint, normal) - pc->radiusA - pc->radiusB;
00645                                 point = clipPoint;
00646                         }
00647                         break;
00648 
00649                 case b2Manifold::e_faceB:
00650                         {
00651                                 normal = b2Mul(xfB.q, pc->localNormal);
00652                                 b2Vec2 planePoint = b2Mul(xfB, pc->localPoint);
00653 
00654                                 b2Vec2 clipPoint = b2Mul(xfA, pc->localPoints[index]);
00655                                 separation = b2Dot(clipPoint - planePoint, normal) - pc->radiusA - pc->radiusB;
00656                                 point = clipPoint;
00657 
00658                                 // Ensure normal points from A to B
00659                                 normal = -normal;
00660                         }
00661                         break;
00662                 }
00663         }
00664 
00665         b2Vec2 normal;
00666         b2Vec2 point;
00667         float32 separation;
00668 };
00669 
00670 // Sequential solver.
00671 bool b2ContactSolver::SolvePositionConstraints()
00672 {
00673         float32 minSeparation = 0.0f;
00674 
00675         for (int32 i = 0; i < m_count; ++i)
00676         {
00677                 b2ContactPositionConstraint* pc = m_positionConstraints + i;
00678 
00679                 int32 indexA = pc->indexA;
00680                 int32 indexB = pc->indexB;
00681                 b2Vec2 localCenterA = pc->localCenterA;
00682                 float32 mA = pc->invMassA;
00683                 float32 iA = pc->invIA;
00684                 b2Vec2 localCenterB = pc->localCenterB;
00685                 float32 mB = pc->invMassB;
00686                 float32 iB = pc->invIB;
00687                 int32 pointCount = pc->pointCount;
00688 
00689                 b2Vec2 cA = m_positions[indexA].c;
00690                 float32 aA = m_positions[indexA].a;
00691 
00692                 b2Vec2 cB = m_positions[indexB].c;
00693                 float32 aB = m_positions[indexB].a;
00694 
00695                 // Solve normal constraints
00696                 for (int32 j = 0; j < pointCount; ++j)
00697                 {
00698                         b2Transform xfA, xfB;
00699                         xfA.q.Set(aA);
00700                         xfB.q.Set(aB);
00701                         xfA.p = cA - b2Mul(xfA.q, localCenterA);
00702                         xfB.p = cB - b2Mul(xfB.q, localCenterB);
00703 
00704                         b2PositionSolverManifold psm;
00705                         psm.Initialize(pc, xfA, xfB, j);
00706                         b2Vec2 normal = psm.normal;
00707 
00708                         b2Vec2 point = psm.point;
00709                         float32 separation = psm.separation;
00710 
00711                         b2Vec2 rA = point - cA;
00712                         b2Vec2 rB = point - cB;
00713 
00714                         // Track max constraint error.
00715                         minSeparation = b2Min(minSeparation, separation);
00716 
00717                         // Prevent large corrections and allow slop.
00718                         float32 C = b2Clamp(b2_baumgarte * (separation + b2_linearSlop), -b2_maxLinearCorrection, 0.0f);
00719 
00720                         // Compute the effective mass.
00721                         float32 rnA = b2Cross(rA, normal);
00722                         float32 rnB = b2Cross(rB, normal);
00723                         float32 K = mA + mB + iA * rnA * rnA + iB * rnB * rnB;
00724 
00725                         // Compute normal impulse
00726                         float32 impulse = K > 0.0f ? - C / K : 0.0f;
00727 
00728                         b2Vec2 P = impulse * normal;
00729 
00730                         cA -= mA * P;
00731                         aA -= iA * b2Cross(rA, P);
00732 
00733                         cB += mB * P;
00734                         aB += iB * b2Cross(rB, P);
00735                 }
00736 
00737                 m_positions[indexA].c = cA;
00738                 m_positions[indexA].a = aA;
00739 
00740                 m_positions[indexB].c = cB;
00741                 m_positions[indexB].a = aB;
00742         }
00743 
00744         // We can't expect minSpeparation >= -b2_linearSlop because we don't
00745         // push the separation above -b2_linearSlop.
00746         return minSeparation >= -3.0f * b2_linearSlop;
00747 }
00748 
00749 // Sequential position solver for position constraints.
00750 bool b2ContactSolver::SolveTOIPositionConstraints(int32 toiIndexA, int32 toiIndexB)
00751 {
00752         float32 minSeparation = 0.0f;
00753 
00754         for (int32 i = 0; i < m_count; ++i)
00755         {
00756                 b2ContactPositionConstraint* pc = m_positionConstraints + i;
00757 
00758                 int32 indexA = pc->indexA;
00759                 int32 indexB = pc->indexB;
00760                 b2Vec2 localCenterA = pc->localCenterA;
00761                 b2Vec2 localCenterB = pc->localCenterB;
00762                 int32 pointCount = pc->pointCount;
00763 
00764                 float32 mA = 0.0f;
00765                 float32 iA = 0.0f;
00766                 if (indexA == toiIndexA || indexA == toiIndexB)
00767                 {
00768                         mA = pc->invMassA;
00769                         iA = pc->invIA;
00770                 }
00771 
00772                 float32 mB = 0.0f;
00773                 float32 iB = 0.;
00774                 if (indexB == toiIndexA || indexB == toiIndexB)
00775                 {
00776                         mB = pc->invMassB;
00777                         iB = pc->invIB;
00778                 }
00779 
00780                 b2Vec2 cA = m_positions[indexA].c;
00781                 float32 aA = m_positions[indexA].a;
00782 
00783                 b2Vec2 cB = m_positions[indexB].c;
00784                 float32 aB = m_positions[indexB].a;
00785 
00786                 // Solve normal constraints
00787                 for (int32 j = 0; j < pointCount; ++j)
00788                 {
00789                         b2Transform xfA, xfB;
00790                         xfA.q.Set(aA);
00791                         xfB.q.Set(aB);
00792                         xfA.p = cA - b2Mul(xfA.q, localCenterA);
00793                         xfB.p = cB - b2Mul(xfB.q, localCenterB);
00794 
00795                         b2PositionSolverManifold psm;
00796                         psm.Initialize(pc, xfA, xfB, j);
00797                         b2Vec2 normal = psm.normal;
00798 
00799                         b2Vec2 point = psm.point;
00800                         float32 separation = psm.separation;
00801 
00802                         b2Vec2 rA = point - cA;
00803                         b2Vec2 rB = point - cB;
00804 
00805                         // Track max constraint error.
00806                         minSeparation = b2Min(minSeparation, separation);
00807 
00808                         // Prevent large corrections and allow slop.
00809                         float32 C = b2Clamp(b2_toiBaugarte * (separation + b2_linearSlop), -b2_maxLinearCorrection, 0.0f);
00810 
00811                         // Compute the effective mass.
00812                         float32 rnA = b2Cross(rA, normal);
00813                         float32 rnB = b2Cross(rB, normal);
00814                         float32 K = mA + mB + iA * rnA * rnA + iB * rnB * rnB;
00815 
00816                         // Compute normal impulse
00817                         float32 impulse = K > 0.0f ? - C / K : 0.0f;
00818 
00819                         b2Vec2 P = impulse * normal;
00820 
00821                         cA -= mA * P;
00822                         aA -= iA * b2Cross(rA, P);
00823 
00824                         cB += mB * P;
00825                         aB += iB * b2Cross(rB, P);
00826                 }
00827 
00828                 m_positions[indexA].c = cA;
00829                 m_positions[indexA].a = aA;
00830 
00831                 m_positions[indexB].c = cB;
00832                 m_positions[indexB].a = aB;
00833         }
00834 
00835         // We can't expect minSpeparation >= -b2_linearSlop because we don't
00836         // push the separation above -b2_linearSlop.
00837         return minSeparation >= -1.5f * b2_linearSlop;
00838 }


mvsim
Author(s):
autogenerated on Thu Jun 6 2019 22:08:34