31         switch (manifold->
type)
    46                         points[0] = 0.5f * (cA + cB);
    61                                 points[i] = 0.5f * (cA + cB);
    77                                 points[i] = 0.5f * (cA + cB);
   144         for (
int32 i = 0; i < 2; ++i)
   149                         if (p(i) < lowerBound(i) || upperBound(i) < p(i))
   157                         float32 t1 = (lowerBound(i) - p(i)) * inv_d;
   158                         float32 t2 = (upperBound(i) - p(i)) * inv_d;
   178                         tmax = 
b2Min(tmax, t2);
   212         if (distance0 <= 0.0
f) vOut[numOut++] = vIn[0];
   213         if (distance1 <= 0.0
f) vOut[numOut++] = vIn[1];
   216         if (distance0 * distance1 < 0.0
f)
   219                 float32 interp = distance0 / (distance0 - distance1);
   220                 vOut[numOut].
v = vIn[0].
v + interp * (vIn[1].
v - vIn[0].
v);
 
point was removed in the update 
float32 b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors. 
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
void Set(const b2Shape *shape, int32 index)
Used for computing contact manifolds. 
b2Vec2 localNormal
not use for Type::e_points 
b2Vec2 points[b2_maxManifoldPoints]
world contact point (point of intersection) 
b2Vec2 normal
world vector pointing from A to B 
b2ContactID id
uniquely identifies a contact point between two shapes 
#define b2_maxManifoldPoints
void SetZero()
Set this vector to all zeros. 
float32 separations[b2_maxManifoldPoints]
a negative value indicates overlap, in meters 
float32 b2DistanceSquared(const b2Vec2 &a, const b2Vec2 &b)
bool RayCast(b2RayCastOutput *output, const b2RayCastInput &input) const 
int32 pointCount
the number of manifold points 
void b2GetPointStates(b2PointState state1[b2_maxManifoldPoints], b2PointState state2[b2_maxManifoldPoints], const b2Manifold *manifold1, const b2Manifold *manifold2)
b2Vec2 localPoint
usage depends on manifold type 
void b2Distance(b2DistanceOutput *output, b2SimplexCache *cache, const b2DistanceInput *input)
b2Vec2 localPoint
usage depends on manifold type 
b2ManifoldPoint points[b2_maxManifoldPoints]
the points of contact 
b2PointState
This is used for determining the state of contact points. 
void Initialize(const b2Manifold *manifold, const b2Transform &xfA, float32 radiusA, const b2Transform &xfB, float32 radiusB)
point persisted across the update 
int32 b2ClipSegmentToLine(b2ClipVertex vOut[2], const b2ClipVertex vIn[2], const b2Vec2 &normal, float32 offset, int32 vertexIndexA)
Clipping for contact manifolds. 
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. 
bool b2TestOverlap(const b2Shape *shapeA, int32 indexA, const b2Shape *shapeB, int32 indexB, const b2Transform &xfA, const b2Transform &xfB)
Determine if two generic shapes overlap. 
point was added in the update