35 switch (manifold->
type)
50 points[0] = 0.5f * (cA + cB);
65 points[i] = 0.5f * (cA + cB);
81 points[i] = 0.5f * (cA + cB);
148 for (
int32 i = 0; i < 2; ++i)
153 if (p(i) < lowerBound(i) || upperBound(i) < p(i))
160 float inv_d = 1.0f / d(i);
161 float t1 = (lowerBound(i) - p(i)) * inv_d;
162 float t2 = (upperBound(i) - p(i)) * inv_d;
182 tmax =
b2Min(tmax, t2);
212 float distance0 =
b2Dot(normal, vIn[0].v) - offset;
213 float distance1 =
b2Dot(normal, vIn[1].v) - offset;
216 if (distance0 <= 0.0
f) vOut[count++] = vIn[0];
217 if (distance1 <= 0.0
f) vOut[count++] = vIn[1];
220 if (distance0 * distance1 < 0.0
f)
223 float interp = distance0 / (distance0 - distance1);
224 vOut[count].
v = vIn[0].
v + interp * (vIn[1].
v - vIn[0].
v);
void Initialize(const b2Manifold *manifold, const b2Transform &xfA, float radiusA, const b2Transform &xfB, float radiusB)
void Set(const b2Shape *shape, int32 index)
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
Used for computing contact manifolds.
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
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
bool RayCast(b2RayCastOutput *output, const b2RayCastInput &input) const
void SetZero()
Set this vector to all zeros.
float b2DistanceSquared(const b2Vec2 &a, const b2Vec2 &b)
void b2GetPointStates(b2PointState state1[b2_maxManifoldPoints], b2PointState state2[b2_maxManifoldPoints], const b2Manifold *manifold1, const b2Manifold *manifold2)
int32 b2ClipSegmentToLine(b2ClipVertex vOut[2], const b2ClipVertex vIn[2], const b2Vec2 &normal, float offset, int32 vertexIndexA)
Clipping for contact manifolds.
void Set(float x_, float y_)
Set this vector to some specified coordinates.
int32 pointCount
the number of manifold points
b2Vec2 localPoint
usage depends on manifold type
point was removed in the update
B2_API void b2Distance(b2DistanceOutput *output, b2SimplexCache *cache, const b2DistanceInput *input)
point was added in the update
b2PointState
This is used for determining the state of contact points.
float separations[b2_maxManifoldPoints]
a negative value indicates overlap, in meters
b2Vec2 localPoint
usage depends on manifold type
b2ManifoldPoint points[b2_maxManifoldPoints]
the points of contact
bool b2TestOverlap(const b2Shape *shapeA, int32 indexA, const b2Shape *shapeB, int32 indexB, const b2Transform &xfA, const b2Transform &xfB)
Determine if two generic shapes overlap.
float Normalize()
Convert this vector into a unit vector. Returns the length.
point persisted across the update