27 #define B2_DEBUG_SOLVER 0 58 for (
int32 i = 0; i < m_count; ++i)
111 if (m_step.warmStarting)
135 m_allocator->Free(m_velocityConstraints);
136 m_allocator->Free(m_positionConstraints);
142 for (
int32 i = 0; i < m_count; ++i)
176 xfA.
p = cA -
b2Mul(xfA.
q, localCenterA);
177 xfB.
p = cB -
b2Mul(xfB.
q, localCenterB);
180 worldManifold.
Initialize(manifold, xfA, radiusA, xfB, radiusB);
189 vcp->
rA = worldManifold.
points[j] - cA;
190 vcp->
rB = worldManifold.
points[j] - cB;
195 float32 kNormal = mA + mB + iA * rnA * rnA + iB * rnB * rnB;
197 vcp->
normalMass = kNormal > 0.0f ? 1.0f / kNormal : 0.0f;
204 float32 kTangent = mA + mB + iA * rtA * rtA + iB * rtB * rtB;
206 vcp->
tangentMass = kTangent > 0.0f ? 1.0f / kTangent : 0.0f;
228 float32 k11 = mA + mB + iA * rn1A * rn1A + iB * rn1B * rn1B;
229 float32 k22 = mA + mB + iA * rn2A * rn2A + iB * rn2B * rn2B;
230 float32 k12 = mA + mB + iA * rn1A * rn2A + iB * rn1B * rn2B;
233 const float32 k_maxConditionNumber = 1000.0f;
234 if (k11 * k11 < k_maxConditionNumber * (k11 * k22 - k12 * k12))
254 for (
int32 i = 0; i < m_count; ++i)
284 m_velocities[
indexA].v = vA;
285 m_velocities[
indexA].w = wA;
286 m_velocities[
indexB].v = vB;
287 m_velocities[
indexB].w = wB;
293 for (
int32 i = 0; i < m_count; ++i)
314 b2Assert(pointCount == 1 || pointCount == 2);
336 b2Vec2 P = lambda * tangent;
365 b2Vec2 P = lambda * normal;
445 if (x.
x >= 0.0f && x.
y >= 0.0f)
453 vA -= mA * (P1 + P2);
456 vB += mB * (P1 + P2);
463 #if B2_DEBUG_SOLVER == 1 469 vn1 =
b2Dot(dv1, normal);
470 vn2 =
b2Dot(dv2, normal);
487 vn2 = vc->
K.
ex.
y * x.
x + b.
y;
489 if (x.
x >= 0.0f && vn2 >= 0.0f)
497 vA -= mA * (P1 + P2);
500 vB += mB * (P1 + P2);
507 #if B2_DEBUG_SOLVER == 1 512 vn1 =
b2Dot(dv1, normal);
528 vn1 = vc->
K.
ey.
x * x.
y + b.
x;
531 if (x.
y >= 0.0f && vn1 >= 0.0f)
539 vA -= mA * (P1 + P2);
542 vB += mB * (P1 + P2);
549 #if B2_DEBUG_SOLVER == 1 554 vn2 =
b2Dot(dv2, normal);
571 if (vn1 >= 0.0f && vn2 >= 0.0f )
579 vA -= mA * (P1 + P2);
582 vB += mB * (P1 + P2);
597 m_velocities[
indexA].v = vA;
598 m_velocities[
indexA].w = wA;
599 m_velocities[
indexB].v = vB;
600 m_velocities[
indexB].w = wB;
606 for (
int32 i = 0; i < m_count; ++i)
631 normal = pointB - pointA;
633 point = 0.5f * (pointA + pointB);
675 for (
int32 i = 0; i < m_count; ++i)
701 xfA.
p = cA -
b2Mul(xfA.
q, localCenterA);
702 xfB.
p = cB -
b2Mul(xfB.
q, localCenterB);
715 minSeparation =
b2Min(minSeparation, separation);
723 float32 K = mA + mB + iA * rnA * rnA + iB * rnB * rnB;
726 float32 impulse = K > 0.0f ? - C / K : 0.0f;
728 b2Vec2 P = impulse * normal;
737 m_positions[
indexA].c = cA;
738 m_positions[
indexA].a = aA;
740 m_positions[
indexB].c = cB;
741 m_positions[
indexB].a = aB;
754 for (
int32 i = 0; i < m_count; ++i)
766 if (indexA == toiIndexA || indexA == toiIndexB)
774 if (indexB == toiIndexA || indexB == toiIndexB)
792 xfA.
p = cA -
b2Mul(xfA.
q, localCenterA);
793 xfB.
p = cB -
b2Mul(xfB.
q, localCenterB);
806 minSeparation =
b2Min(minSeparation, separation);
814 float32 K = mA + mB + iA * rnA * rnA + iB * rnB * rnB;
817 float32 impulse = K > 0.0f ? - C / K : 0.0f;
819 b2Vec2 P = impulse * normal;
828 m_positions[
indexA].c = cA;
829 m_positions[
indexA].a = aA;
831 m_positions[
indexB].c = cB;
832 m_positions[
indexB].a = aB;
GLboolean GLboolean GLboolean GLboolean a
float32 b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
b2Vec2 localNormal
not use for Type::e_points
b2Vec2 points[b2_maxManifoldPoints]
world contact point (point of intersection)
void SetZero()
Set this matrix to all zeros.
b2Vec2 normal
world vector pointing from A to B
#define b2_maxManifoldPoints
void SetZero()
Set this vector to all zeros.
#define b2_maxLinearCorrection
b2Vec2 localCenter
local center of mass position
float32 b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
void Initialize(b2ContactPositionConstraint *pc, const b2Transform &xfA, const b2Transform &xfB, int32 index)
A rigid body. These are created via b2World::CreateBody.
GLint GLint GLint GLint GLint x
int32 pointCount
the number of manifold points
b2Vec2 localPoint
usage depends on manifold type
float32 tangentImpulse
the friction impulse
b2Vec2 localPoint
usage depends on manifold type
b2ManifoldPoint points[b2_maxManifoldPoints]
the points of contact
void Set(float32 angle)
Set using an angle in radians.
T b2Clamp(T a, T low, T high)
void Initialize(const b2Manifold *manifold, const b2Transform &xfA, float32 radiusA, const b2Transform &xfB, float32 radiusB)
GLdouble GLdouble GLdouble b
float32 Normalize()
Convert this vector into a unit vector. Returns the length.
void Set(float32 x_, float32 y_)
Set this vector to some specified coordinates.
#define b2_velocityThreshold
b2Mat22 GetInverse() const
This is used to compute the current state of a contact manifold.
float32 normalImpulse
the non-penetration impulse
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f