rename RcVecUtils to RcVec

This commit is contained in:
ikpil 2024-06-25 00:02:59 +09:00
parent 72b7cfd6db
commit e5d5867c56
30 changed files with 158 additions and 153 deletions

View File

@ -3,9 +3,10 @@ using System.Runtime.CompilerServices;
namespace DotRecast.Core.Numerics namespace DotRecast.Core.Numerics
{ {
public static class RcVecUtils public static class RcVec
{ {
public const float EPSILON = 1e-6f; public const float EPSILON = 1e-6f;
private static readonly float EQUAL_THRESHOLD = RcMath.Sqr(1.0f / 16384.0f);
[MethodImpl(MethodImplOptions.AggressiveInlining)] [MethodImpl(MethodImplOptions.AggressiveInlining)]
public static RcVec3f Create(Span<float> values, int n) public static RcVec3f Create(Span<float> values, int n)
@ -36,12 +37,28 @@ namespace DotRecast.Core.Numerics
} }
} }
/// Performs a 'sloppy' colocation check of the specified points.
/// @param[in] p0 A point. [(x, y, z)]
/// @param[in] p1 A point. [(x, y, z)]
/// @return True if the points are considered to be at the same location.
///
/// Basically, this function will return true if the specified points are
/// close enough to eachother to be considered colocated.
public static bool Equal(RcVec3f p0, RcVec3f p1)
{
float d = RcVec3f.DistanceSquared(p0, p1);
return d < EQUAL_THRESHOLD;
}
[MethodImpl(MethodImplOptions.AggressiveInlining)]
public static float Dot2(RcVec3f a, RcVec3f b) public static float Dot2(RcVec3f a, RcVec3f b)
{ {
return a.X * b.X + a.Z * b.Z; return a.X * b.X + a.Z * b.Z;
} }
[MethodImpl(MethodImplOptions.AggressiveInlining)]
public static float DistSq2(float[] verts, int p, int q) public static float DistSq2(float[] verts, int p, int q)
{ {
float dx = verts[q + 0] - verts[p + 0]; float dx = verts[q + 0] - verts[p + 0];
@ -49,11 +66,13 @@ namespace DotRecast.Core.Numerics
return dx * dx + dy * dy; return dx * dx + dy * dy;
} }
[MethodImpl(MethodImplOptions.AggressiveInlining)]
public static float Dist2(float[] verts, int p, int q) public static float Dist2(float[] verts, int p, int q)
{ {
return MathF.Sqrt(DistSq2(verts, p, q)); return MathF.Sqrt(DistSq2(verts, p, q));
} }
[MethodImpl(MethodImplOptions.AggressiveInlining)]
public static float DistSq2(RcVec3f p, RcVec3f q) public static float DistSq2(RcVec3f p, RcVec3f q)
{ {
float dx = q.X - p.X; float dx = q.X - p.X;
@ -61,11 +80,13 @@ namespace DotRecast.Core.Numerics
return dx * dx + dy * dy; return dx * dx + dy * dy;
} }
[MethodImpl(MethodImplOptions.AggressiveInlining)]
public static float Dist2(RcVec3f p, RcVec3f q) public static float Dist2(RcVec3f p, RcVec3f q)
{ {
return MathF.Sqrt(DistSq2(p, q)); return MathF.Sqrt(DistSq2(p, q));
} }
[MethodImpl(MethodImplOptions.AggressiveInlining)]
public static float Cross2(float[] verts, int p1, int p2, int p3) public static float Cross2(float[] verts, int p1, int p2, int p3)
{ {
float u1 = verts[p2 + 0] - verts[p1 + 0]; float u1 = verts[p2 + 0] - verts[p1 + 0];
@ -75,6 +96,7 @@ namespace DotRecast.Core.Numerics
return u1 * v2 - v1 * u2; return u1 * v2 - v1 * u2;
} }
[MethodImpl(MethodImplOptions.AggressiveInlining)]
public static float Cross2(RcVec3f p1, RcVec3f p2, RcVec3f p3) public static float Cross2(RcVec3f p1, RcVec3f p2, RcVec3f p3)
{ {
float u1 = p2.X - p1.X; float u1 = p2.X - p1.X;
@ -83,7 +105,7 @@ namespace DotRecast.Core.Numerics
float v2 = p3.Z - p1.Z; float v2 = p3.Z - p1.Z;
return u1 * v2 - v1 * u2; return u1 * v2 - v1 * u2;
} }
/// Derives the dot product of two vectors on the xz-plane. (@p u . @p v) /// Derives the dot product of two vectors on the xz-plane. (@p u . @p v)
/// @param[in] u A vector [(x, y, z)] /// @param[in] u A vector [(x, y, z)]
/// @param[in] v A vector [(x, y, z)] /// @param[in] v A vector [(x, y, z)]
@ -162,6 +184,10 @@ namespace DotRecast.Core.Numerics
return (float)MathF.Sqrt(dx * dx + dz * dz); return (float)MathF.Sqrt(dx * dx + dz * dz);
} }
/// Derives the square of the distance between the specified points on the xz-plane.
/// @param[in] v1 A point. [(x, y, z)]
/// @param[in] v2 A point. [(x, y, z)]
/// @return The square of the distance between the point on the xz-plane.
[MethodImpl(MethodImplOptions.AggressiveInlining)] [MethodImpl(MethodImplOptions.AggressiveInlining)]
public static float Dist2DSqr(RcVec3f v1, RcVec3f v2) public static float Dist2DSqr(RcVec3f v1, RcVec3f v2)
{ {

View File

@ -875,7 +875,7 @@ namespace DotRecast.Detour.Crowd
// Update the collision boundary after certain distance has been passed or // Update the collision boundary after certain distance has been passed or
// if it has become invalid. // if it has become invalid.
float updateThr = ag.option.collisionQueryRange * 0.25f; float updateThr = ag.option.collisionQueryRange * 0.25f;
if (RcVecUtils.Dist2DSqr(ag.npos, ag.boundary.GetCenter()) > RcMath.Sqr(updateThr) if (RcVec.Dist2DSqr(ag.npos, ag.boundary.GetCenter()) > RcMath.Sqr(updateThr)
|| !ag.boundary.IsValid(_navQuery, _filters[ag.option.queryFilterType])) || !ag.boundary.IsValid(_navQuery, _filters[ag.option.queryFilterType]))
{ {
ag.boundary.Update(ag.corridor.GetFirstPoly(), ag.npos, ag.option.collisionQueryRange, _navQuery, ag.boundary.Update(ag.corridor.GetFirstPoly(), ag.npos, ag.option.collisionQueryRange, _navQuery,
@ -1007,7 +1007,7 @@ namespace DotRecast.Detour.Crowd
anim.polyRef = refs[1]; anim.polyRef = refs[1];
anim.active = true; anim.active = true;
anim.t = 0.0f; anim.t = 0.0f;
anim.tmax = (RcVecUtils.Dist2D(anim.startPos, anim.endPos) / ag.option.maxSpeed) * 0.5f; anim.tmax = (RcVec.Dist2D(anim.startPos, anim.endPos) / ag.option.maxSpeed) * 0.5f;
ag.state = DtCrowdAgentState.DT_CROWDAGENT_STATE_OFFMESH; ag.state = DtCrowdAgentState.DT_CROWDAGENT_STATE_OFFMESH;
ag.ncorners = 0; ag.ncorners = 0;
@ -1097,14 +1097,14 @@ namespace DotRecast.Detour.Crowd
float dist = MathF.Sqrt(distSqr); float dist = MathF.Sqrt(distSqr);
float weight = separationWeight * (1.0f - RcMath.Sqr(dist * invSeparationDist)); float weight = separationWeight * (1.0f - RcMath.Sqr(dist * invSeparationDist));
disp = RcVecUtils.Mad(disp, diff, weight / dist); disp = RcVec.Mad(disp, diff, weight / dist);
w += 1.0f; w += 1.0f;
} }
if (w > 0.0001f) if (w > 0.0001f)
{ {
// Adjust desired velocity. // Adjust desired velocity.
dvel = RcVecUtils.Mad(dvel, disp, 1.0f / w); dvel = RcVec.Mad(dvel, disp, 1.0f / w);
// Clamp desired velocity to desired speed. // Clamp desired velocity to desired speed.
float speedSqr = dvel.LengthSquared(); float speedSqr = dvel.LengthSquared();
float desiredSqr = RcMath.Sqr(ag.desiredSpeed); float desiredSqr = RcMath.Sqr(ag.desiredSpeed);
@ -1260,7 +1260,7 @@ namespace DotRecast.Detour.Crowd
pen = (1.0f / dist) * (pen * 0.5f) * _config.collisionResolveFactor; pen = (1.0f / dist) * (pen * 0.5f) * _config.collisionResolveFactor;
} }
ag.disp = RcVecUtils.Mad(ag.disp, diff, pen); ag.disp = RcVec.Mad(ag.disp, diff, pen);
w += 1.0f; w += 1.0f;
} }

View File

@ -96,7 +96,7 @@ namespace DotRecast.Detour.Crowd
// Integrate // Integrate
if (vel.Length() > 0.0001f) if (vel.Length() > 0.0001f)
npos = RcVecUtils.Mad(npos, vel, dt); npos = RcVec.Mad(npos, vel, dt);
else else
vel = RcVec3f.Zero; vel = RcVec3f.Zero;
} }
@ -112,7 +112,7 @@ namespace DotRecast.Detour.Crowd
: false; : false;
if (offMeshConnection) if (offMeshConnection)
{ {
float distSq = RcVecUtils.Dist2DSqr(npos, corners[ncorners - 1].pos); float distSq = RcVec.Dist2DSqr(npos, corners[ncorners - 1].pos);
if (distSq < radius * radius) if (distSq < radius * radius)
return true; return true;
} }
@ -127,7 +127,7 @@ namespace DotRecast.Detour.Crowd
bool endOfPath = ((corners[ncorners - 1].flags & DtStraightPathFlags.DT_STRAIGHTPATH_END) != 0) ? true : false; bool endOfPath = ((corners[ncorners - 1].flags & DtStraightPathFlags.DT_STRAIGHTPATH_END) != 0) ? true : false;
if (endOfPath) if (endOfPath)
return Math.Min(RcVecUtils.Dist2D(npos, corners[ncorners - 1].pos), range); return Math.Min(RcVec.Dist2D(npos, corners[ncorners - 1].pos), range);
return range; return range;
} }

View File

@ -186,16 +186,16 @@ namespace DotRecast.Detour.Crowd
{ {
RcVec3f v = RcVec3f.Subtract(bq, bp); RcVec3f v = RcVec3f.Subtract(bq, bp);
RcVec3f w = RcVec3f.Subtract(ap, bp); RcVec3f w = RcVec3f.Subtract(ap, bp);
float d = RcVecUtils.Perp2D(u, v); float d = RcVec.Perp2D(u, v);
if (MathF.Abs(d) < 1e-6f) if (MathF.Abs(d) < 1e-6f)
return false; return false;
d = 1.0f / d; d = 1.0f / d;
t = RcVecUtils.Perp2D(v, w) * d; t = RcVec.Perp2D(v, w) * d;
if (t < 0 || t > 1) if (t < 0 || t > 1)
return false; return false;
float s = RcVecUtils.Perp2D(u, w) * d; float s = RcVec.Perp2D(u, w) * d;
if (s < 0 || s > 1) if (s < 0 || s > 1)
return false; return false;
@ -216,8 +216,8 @@ namespace DotRecast.Detour.Crowd
float minPenalty, DtObstacleAvoidanceDebugData debug) float minPenalty, DtObstacleAvoidanceDebugData debug)
{ {
// penalty for straying away from the desired and current velocities // penalty for straying away from the desired and current velocities
float vpen = m_params.weightDesVel * (RcVecUtils.Dist2D(vcand, dvel) * m_invVmax); float vpen = m_params.weightDesVel * (RcVec.Dist2D(vcand, dvel) * m_invVmax);
float vcpen = m_params.weightCurVel * (RcVecUtils.Dist2D(vcand, vel) * m_invVmax); float vcpen = m_params.weightCurVel * (RcVec.Dist2D(vcand, vel) * m_invVmax);
// find the threshold hit time to bail out based on the early out penalty // find the threshold hit time to bail out based on the early out penalty
// (see how the penalty is calculated below to understand) // (see how the penalty is calculated below to understand)

View File

@ -144,7 +144,7 @@ namespace DotRecast.Detour.Crowd
while (0 < ncorners) while (0 < ncorners)
{ {
if ((corners[0].flags & DtStraightPathFlags.DT_STRAIGHTPATH_OFFMESH_CONNECTION) != 0 || if ((corners[0].flags & DtStraightPathFlags.DT_STRAIGHTPATH_OFFMESH_CONNECTION) != 0 ||
RcVecUtils.Dist2DSqr(corners[0].pos, m_pos) > RcMath.Sqr(MIN_TARGET_DIST)) RcVec.Dist2DSqr(corners[0].pos, m_pos) > RcMath.Sqr(MIN_TARGET_DIST))
{ {
break; break;
} }
@ -197,7 +197,7 @@ namespace DotRecast.Detour.Crowd
public void OptimizePathVisibility(RcVec3f next, float pathOptimizationRange, DtNavMeshQuery navquery, IDtQueryFilter filter) public void OptimizePathVisibility(RcVec3f next, float pathOptimizationRange, DtNavMeshQuery navquery, IDtQueryFilter filter)
{ {
// Clamp the ray to max distance. // Clamp the ray to max distance.
float dist = RcVecUtils.Dist2D(m_pos, next); float dist = RcVec.Dist2D(m_pos, next);
// If too close to the goal, do not try to optimize. // If too close to the goal, do not try to optimize.
if (dist < 0.01f) if (dist < 0.01f)
@ -210,7 +210,7 @@ namespace DotRecast.Detour.Crowd
// Adjust ray length. // Adjust ray length.
var delta = RcVec3f.Subtract(next, m_pos); var delta = RcVec3f.Subtract(next, m_pos);
RcVec3f goal = RcVecUtils.Mad(m_pos, delta, pathOptimizationRange / dist); RcVec3f goal = RcVec.Mad(m_pos, delta, pathOptimizationRange / dist);
var res = new List<long>(); var res = new List<long>();
var status = navquery.Raycast(m_path[0], m_pos, goal, filter, out var t, out var norm, ref res); var status = navquery.Raycast(m_path[0], m_pos, goal, filter, out var t, out var norm, ref res);

View File

@ -40,12 +40,12 @@ namespace DotRecast.Detour.Extras
BVItem it = new BVItem(); BVItem it = new BVItem();
items[i] = it; items[i] = it;
it.i = i; it.i = i;
RcVec3f bmin = RcVecUtils.Create(data.verts, data.polys[i].verts[0] * 3); RcVec3f bmin = RcVec.Create(data.verts, data.polys[i].verts[0] * 3);
RcVec3f bmax = RcVecUtils.Create(data.verts, data.polys[i].verts[0] * 3); RcVec3f bmax = RcVec.Create(data.verts, data.polys[i].verts[0] * 3);
for (int j = 1; j < data.polys[i].vertCount; j++) for (int j = 1; j < data.polys[i].vertCount; j++)
{ {
bmin = RcVec3f.Min(bmin, RcVecUtils.Create(data.verts, data.polys[i].verts[j] * 3)); bmin = RcVec3f.Min(bmin, RcVec.Create(data.verts, data.polys[i].verts[j] * 3));
bmax = RcVec3f.Max(bmax, RcVecUtils.Create(data.verts, data.polys[i].verts[j] * 3)); bmax = RcVec3f.Max(bmax, RcVec.Create(data.verts, data.polys[i].verts[j] * 3));
} }
it.bmin[0] = Math.Clamp((int)((bmin.X - data.header.bmin.X) * quantFactor), 0, 0x7fffffff); it.bmin[0] = Math.Clamp((int)((bmin.X - data.header.bmin.X) * quantFactor), 0, 0x7fffffff);

View File

@ -11,7 +11,7 @@ namespace DotRecast.Detour.Extras.Jumplink
protected void SampleGround(JumpLinkBuilderConfig acfg, EdgeSampler es, ComputeNavMeshHeight heightFunc) protected void SampleGround(JumpLinkBuilderConfig acfg, EdgeSampler es, ComputeNavMeshHeight heightFunc)
{ {
float cs = acfg.cellSize; float cs = acfg.cellSize;
float dist = MathF.Sqrt(RcVecUtils.Dist2DSqr(es.start.p, es.start.q)); float dist = MathF.Sqrt(RcVec.Dist2DSqr(es.start.p, es.start.q));
int ngsamples = Math.Max(2, (int)MathF.Ceiling(dist / cs)); int ngsamples = Math.Max(2, (int)MathF.Ceiling(dist / cs));
SampleGroundSegment(heightFunc, es.start, ngsamples); SampleGroundSegment(heightFunc, es.start, ngsamples);

View File

@ -59,7 +59,7 @@ namespace DotRecast.Detour.Extras.Jumplink
GroundSegment end = es.end[js.groundSegment]; GroundSegment end = es.end[js.groundSegment];
RcVec3f ep = end.gsamples[js.startSample].p; RcVec3f ep = end.gsamples[js.startSample].p;
RcVec3f eq = end.gsamples[js.startSample + js.samples - 1].p; RcVec3f eq = end.gsamples[js.startSample + js.samples - 1].p;
float d = Math.Min(RcVecUtils.Dist2DSqr(sp, sq), RcVecUtils.Dist2DSqr(ep, eq)); float d = Math.Min(RcVec.Dist2DSqr(sp, sq), RcVec.Dist2DSqr(ep, eq));
if (d >= 4 * acfg.agentRadius * acfg.agentRadius) if (d >= 4 * acfg.agentRadius * acfg.agentRadius)
{ {
JumpLink link = new JumpLink(); JumpLink link = new JumpLink();

View File

@ -35,7 +35,7 @@ namespace DotRecast.Detour.Extras.Jumplink
private bool SampleTrajectory(JumpLinkBuilderConfig acfg, RcHeightfield solid, RcVec3f pa, RcVec3f pb, ITrajectory tra) private bool SampleTrajectory(JumpLinkBuilderConfig acfg, RcHeightfield solid, RcVec3f pa, RcVec3f pb, ITrajectory tra)
{ {
float cs = Math.Min(acfg.cellSize, acfg.cellHeight); float cs = Math.Min(acfg.cellSize, acfg.cellHeight);
float d = RcVecUtils.Dist2D(pa, pb) + MathF.Abs(pa.Y - pb.Y); float d = RcVec.Dist2D(pa, pb) + MathF.Abs(pa.Y - pb.Y);
int nsamples = Math.Max(2, (int)MathF.Ceiling(d / cs)); int nsamples = Math.Max(2, (int)MathF.Ceiling(d / cs));
for (int i = 0; i < nsamples; ++i) for (int i = 0; i < nsamples; ++i)
{ {

View File

@ -54,10 +54,10 @@ namespace DotRecast.Detour
do do
{ {
a = RcVecUtils.Create(p, 3 * (ai % n)); a = RcVec.Create(p, 3 * (ai % n));
b = RcVecUtils.Create(q, 3 * (bi % m)); b = RcVec.Create(q, 3 * (bi % m));
a1 = RcVecUtils.Create(p, 3 * ((ai + n - 1) % n)); // prev a a1 = RcVec.Create(p, 3 * ((ai + n - 1) % n)); // prev a
b1 = RcVecUtils.Create(q, 3 * ((bi + m - 1) % m)); // prev b b1 = RcVec.Create(q, 3 * ((bi + m - 1) % m)); // prev b
RcVec3f A = RcVec3f.Subtract(a, a1); RcVec3f A = RcVec3f.Subtract(a, a1);
RcVec3f B = RcVec3f.Subtract(b, b1); RcVec3f B = RcVec3f.Subtract(b, b1);

View File

@ -319,13 +319,13 @@ namespace DotRecast.Detour
// Calc polygon bounds. // Calc polygon bounds.
int v = p.verts[0] * 3; int v = p.verts[0] * 3;
bmin = RcVecUtils.Create(tile.data.verts, v); bmin = RcVec.Create(tile.data.verts, v);
bmax = RcVecUtils.Create(tile.data.verts, v); bmax = RcVec.Create(tile.data.verts, v);
for (int j = 1; j < p.vertCount; ++j) for (int j = 1; j < p.vertCount; ++j)
{ {
v = p.verts[j] * 3; v = p.verts[j] * 3;
bmin = RcVec3f.Min(bmin, RcVecUtils.Create(tile.data.verts, v)); bmin = RcVec3f.Min(bmin, RcVec.Create(tile.data.verts, v));
bmax = RcVec3f.Max(bmax, RcVecUtils.Create(tile.data.verts, v)); bmax = RcVec3f.Max(bmax, RcVec.Create(tile.data.verts, v));
} }
if (DtUtils.OverlapBounds(qmin, qmax, bmin, bmax)) if (DtUtils.OverlapBounds(qmin, qmax, bmin, bmax))
@ -1489,8 +1489,8 @@ namespace DotRecast.Detour
} }
} }
startPos = RcVecUtils.Create(tile.data.verts, poly.verts[idx0] * 3); startPos = RcVec.Create(tile.data.verts, poly.verts[idx0] * 3);
endPos = RcVecUtils.Create(tile.data.verts, poly.verts[idx1] * 3); endPos = RcVec.Create(tile.data.verts, poly.verts[idx1] * 3);
return DtStatus.DT_SUCCESS; return DtStatus.DT_SUCCESS;
} }

View File

@ -164,12 +164,12 @@ namespace DotRecast.Detour
int vb = option.detailMeshes[i * 4 + 0]; int vb = option.detailMeshes[i * 4 + 0];
int ndv = option.detailMeshes[i * 4 + 1]; int ndv = option.detailMeshes[i * 4 + 1];
int dv = vb * 3; int dv = vb * 3;
var bmin = RcVecUtils.Create(option.detailVerts, dv); var bmin = RcVec.Create(option.detailVerts, dv);
var bmax = RcVecUtils.Create(option.detailVerts, dv); var bmax = RcVec.Create(option.detailVerts, dv);
for (int j = 1; j < ndv; j++) for (int j = 1; j < ndv; j++)
{ {
bmin = RcVec3f.Min(bmin, RcVecUtils.Create(option.detailVerts, dv + j * 3)); bmin = RcVec3f.Min(bmin, RcVec.Create(option.detailVerts, dv + j * 3));
bmax = RcVec3f.Max(bmax, RcVecUtils.Create(option.detailVerts, dv + j * 3)); bmax = RcVec3f.Max(bmax, RcVec.Create(option.detailVerts, dv + j * 3));
} }
// BV-tree uses cs for all dimensions // BV-tree uses cs for all dimensions
@ -322,8 +322,8 @@ namespace DotRecast.Detour
for (int i = 0; i < option.offMeshConCount; ++i) for (int i = 0; i < option.offMeshConCount; ++i)
{ {
var p0 = RcVecUtils.Create(option.offMeshConVerts, (i * 2 + 0) * 3); var p0 = RcVec.Create(option.offMeshConVerts, (i * 2 + 0) * 3);
var p1 = RcVecUtils.Create(option.offMeshConVerts, (i * 2 + 1) * 3); var p1 = RcVec.Create(option.offMeshConVerts, (i * 2 + 1) * 3);
offMeshConClass[i * 2 + 0] = ClassifyOffMeshPoint(p0, bmin, bmax); offMeshConClass[i * 2 + 0] = ClassifyOffMeshPoint(p0, bmin, bmax);
offMeshConClass[i * 2 + 1] = ClassifyOffMeshPoint(p1, bmin, bmax); offMeshConClass[i * 2 + 1] = ClassifyOffMeshPoint(p1, bmin, bmax);
@ -624,7 +624,7 @@ namespace DotRecast.Detour
int endPts = i * 2 * 3; int endPts = i * 2 * 3;
for (int j = 0; j < 2; ++j) for (int j = 0; j < 2; ++j)
{ {
con.pos[j] = RcVecUtils.Create(option.offMeshConVerts, endPts + (j * 3)); con.pos[j] = RcVec.Create(option.offMeshConVerts, endPts + (j * 3));
} }
con.rad = option.offMeshConRad[i]; con.rad = option.offMeshConRad[i];

View File

@ -487,7 +487,7 @@ namespace DotRecast.Detour
int va = imin * 3; int va = imin * 3;
int vb = ((imin + 1) % nv) * 3; int vb = ((imin + 1) % nv) * 3;
closest = RcVecUtils.Lerp(verts, va, vb, edget[imin]); closest = RcVec.Lerp(verts, va, vb, edget[imin]);
} }
return DtStatus.DT_SUCCESS; return DtStatus.DT_SUCCESS;
@ -670,13 +670,13 @@ namespace DotRecast.Detour
// Calc polygon bounds. // Calc polygon bounds.
int v = p.verts[0] * 3; int v = p.verts[0] * 3;
bmin = RcVecUtils.Create(tile.data.verts, v); bmin = RcVec.Create(tile.data.verts, v);
bmax = RcVecUtils.Create(tile.data.verts, v); bmax = RcVec.Create(tile.data.verts, v);
for (int j = 1; j < p.vertCount; ++j) for (int j = 1; j < p.vertCount; ++j)
{ {
v = p.verts[j] * 3; v = p.verts[j] * 3;
bmin = RcVec3f.Min(bmin, RcVecUtils.Create(tile.data.verts, v)); bmin = RcVec3f.Min(bmin, RcVec.Create(tile.data.verts, v));
bmax = RcVec3f.Max(bmax, RcVecUtils.Create(tile.data.verts, v)); bmax = RcVec3f.Max(bmax, RcVec.Create(tile.data.verts, v));
} }
if (DtUtils.OverlapBounds(qmin, qmax, bmin, bmax)) if (DtUtils.OverlapBounds(qmin, qmax, bmin, bmax))
@ -1479,7 +1479,7 @@ namespace DotRecast.Detour
protected DtStatus AppendVertex(RcVec3f pos, int flags, long refs, Span<DtStraightPath> straightPath, ref int straightPathCount, int maxStraightPath) protected DtStatus AppendVertex(RcVec3f pos, int flags, long refs, Span<DtStraightPath> straightPath, ref int straightPathCount, int maxStraightPath)
{ {
if (straightPathCount > 0 && DtUtils.VEqual(straightPath[straightPathCount - 1].pos, pos)) if (straightPathCount > 0 && RcVec.Equal(straightPath[straightPathCount - 1].pos, pos))
{ {
// The vertices are equal, update flags and poly. // The vertices are equal, update flags and poly.
straightPath[straightPathCount - 1] = new DtStraightPath(straightPath[straightPathCount - 1].pos, flags, refs); straightPath[straightPathCount - 1] = new DtStraightPath(straightPath[straightPathCount - 1].pos, flags, refs);
@ -1693,7 +1693,7 @@ namespace DotRecast.Detour
// Right vertex. // Right vertex.
if (DtUtils.TriArea2D(portalApex, portalRight, right) <= 0.0f) if (DtUtils.TriArea2D(portalApex, portalRight, right) <= 0.0f)
{ {
if (DtUtils.VEqual(portalApex, portalRight) || DtUtils.TriArea2D(portalApex, portalLeft, right) > 0.0f) if (RcVec.Equal(portalApex, portalRight) || DtUtils.TriArea2D(portalApex, portalLeft, right) > 0.0f)
{ {
portalRight = right; portalRight = right;
rightPolyRef = (i + 1 < pathSize) ? path[i + 1] : 0; rightPolyRef = (i + 1 < pathSize) ? path[i + 1] : 0;
@ -1749,7 +1749,7 @@ namespace DotRecast.Detour
// Left vertex. // Left vertex.
if (DtUtils.TriArea2D(portalApex, portalLeft, left) >= 0.0f) if (DtUtils.TriArea2D(portalApex, portalLeft, left) >= 0.0f)
{ {
if (DtUtils.VEqual(portalApex, portalLeft) || DtUtils.TriArea2D(portalApex, portalRight, left) < 0.0f) if (RcVec.Equal(portalApex, portalLeft) || DtUtils.TriArea2D(portalApex, portalRight, left) < 0.0f)
{ {
portalLeft = left; portalLeft = left;
leftPolyRef = (i + 1 < pathSize) ? path[i + 1] : 0; leftPolyRef = (i + 1 < pathSize) ? path[i + 1] : 0;
@ -1965,7 +1965,7 @@ namespace DotRecast.Detour
if (distSqr < bestDist) if (distSqr < bestDist)
{ {
// Update nearest distance. // Update nearest distance.
bestPos = RcVecUtils.Lerp(verts, vj, vi, tseg); bestPos = RcVec.Lerp(verts, vj, vi, tseg);
bestDist = distSqr; bestDist = distSqr;
bestNode = curNode; bestNode = curNode;
} }
@ -2153,8 +2153,8 @@ namespace DotRecast.Detour
float s = 1.0f / 255.0f; float s = 1.0f / 255.0f;
float tmin = link.bmin * s; float tmin = link.bmin * s;
float tmax = link.bmax * s; float tmax = link.bmax * s;
left = RcVecUtils.Lerp(fromTile.data.verts, v0 * 3, v1 * 3, tmin); left = RcVec.Lerp(fromTile.data.verts, v0 * 3, v1 * 3, tmin);
right = RcVecUtils.Lerp(fromTile.data.verts, v0 * 3, v1 * 3, tmax); right = RcVec.Lerp(fromTile.data.verts, v0 * 3, v1 * 3, tmax);
} }
} }
@ -2345,7 +2345,7 @@ namespace DotRecast.Detour
int nv = 0; int nv = 0;
for (int i = 0; i < poly.vertCount; ++i) for (int i = 0; i < poly.vertCount; ++i)
{ {
verts[nv] = RcVecUtils.Create(tile.data.verts, poly.verts[i] * 3); verts[nv] = RcVec.Create(tile.data.verts, poly.verts[i] * 3);
nv++; nv++;
} }
@ -2483,7 +2483,7 @@ namespace DotRecast.Detour
// compute the intersection point at the furthest end of the polygon // compute the intersection point at the furthest end of the polygon
// and correct the height (since the raycast moves in 2d) // and correct the height (since the raycast moves in 2d)
lastPos = curPos; lastPos = curPos;
curPos = RcVecUtils.Mad(startPos, dir, hit.t); curPos = RcVec.Mad(startPos, dir, hit.t);
var e1 = verts[segMax]; var e1 = verts[segMax];
var e2 = verts[(segMax + 1) % nv]; var e2 = verts[(segMax + 1) % nv];
var eDir = RcVec3f.Subtract(e2, e1); var eDir = RcVec3f.Subtract(e2, e1);
@ -3174,8 +3174,8 @@ namespace DotRecast.Detour
int ivj = poly.verts[j] * 3; int ivj = poly.verts[j] * 3;
int ivi = poly.verts[i] * 3; int ivi = poly.verts[i] * 3;
var seg = new RcSegmentVert(); var seg = new RcSegmentVert();
seg.vmin = RcVecUtils.Create(tile.data.verts, ivj); seg.vmin = RcVec.Create(tile.data.verts, ivj);
seg.vmax = RcVecUtils.Create(tile.data.verts, ivi); seg.vmax = RcVec.Create(tile.data.verts, ivi);
// RcArrays.Copy(tile.data.verts, ivj, seg, 0, 3); // RcArrays.Copy(tile.data.verts, ivj, seg, 0, 3);
// RcArrays.Copy(tile.data.verts, ivi, seg, 3, 3); // RcArrays.Copy(tile.data.verts, ivi, seg, 3, 3);
segmentVerts.Add(seg); segmentVerts.Add(seg);
@ -3198,8 +3198,8 @@ namespace DotRecast.Detour
float tmin = ints[k].tmin / 255.0f; float tmin = ints[k].tmin / 255.0f;
float tmax = ints[k].tmax / 255.0f; float tmax = ints[k].tmax / 255.0f;
var seg = new RcSegmentVert(); var seg = new RcSegmentVert();
seg.vmin = RcVecUtils.Lerp(tile.data.verts, vj, vi, tmin); seg.vmin = RcVec.Lerp(tile.data.verts, vj, vi, tmin);
seg.vmax = RcVecUtils.Lerp(tile.data.verts, vj, vi, tmax); seg.vmax = RcVec.Lerp(tile.data.verts, vj, vi, tmax);
segmentVerts.Add(seg); segmentVerts.Add(seg);
segmentRefs.Add(ints[k].refs); segmentRefs.Add(ints[k].refs);
} }
@ -3212,8 +3212,8 @@ namespace DotRecast.Detour
float tmin = imin / 255.0f; float tmin = imin / 255.0f;
float tmax = imax / 255.0f; float tmax = imax / 255.0f;
var seg = new RcSegmentVert(); var seg = new RcSegmentVert();
seg.vmin = RcVecUtils.Lerp(tile.data.verts, vj, vi, tmin); seg.vmin = RcVec.Lerp(tile.data.verts, vj, vi, tmin);
seg.vmax = RcVecUtils.Lerp(tile.data.verts, vj, vi, tmax); seg.vmax = RcVec.Lerp(tile.data.verts, vj, vi, tmax);
segmentVerts.Add(seg); segmentVerts.Add(seg);
segmentRefs.Add(0L); segmentRefs.Add(0L);
} }
@ -3355,8 +3355,8 @@ namespace DotRecast.Detour
hitPos.Y = bestTile.data.verts[vj + 1] + (bestTile.data.verts[vi + 1] - bestTile.data.verts[vj + 1]) * tseg; hitPos.Y = bestTile.data.verts[vj + 1] + (bestTile.data.verts[vi + 1] - bestTile.data.verts[vj + 1]) * tseg;
hitPos.Z = bestTile.data.verts[vj + 2] + (bestTile.data.verts[vi + 2] - bestTile.data.verts[vj + 2]) * tseg; hitPos.Z = bestTile.data.verts[vj + 2] + (bestTile.data.verts[vi + 2] - bestTile.data.verts[vj + 2]) * tseg;
hasBestV = true; hasBestV = true;
bestvj = RcVecUtils.Create(bestTile.data.verts, vj); bestvj = RcVec.Create(bestTile.data.verts, vj);
bestvi = RcVecUtils.Create(bestTile.data.verts, vi); bestvi = RcVec.Create(bestTile.data.verts, vi);
} }
for (int i = bestPoly.firstLink; i != DT_NULL_LINK; i = bestTile.links[i].next) for (int i = bestPoly.firstLink; i != DT_NULL_LINK; i = bestTile.links[i].next)

View File

@ -37,7 +37,7 @@ namespace DotRecast.Detour
int outsideVertex = -1; int outsideVertex = -1;
for (int pv = 0; pv < verts.Length; pv += 3) for (int pv = 0; pv < verts.Length; pv += 3)
{ {
if (RcVecUtils.Dist2DSqr(center, verts, pv) > radiusSqr) if (RcVec.Dist2DSqr(center, verts, pv) > radiusSqr)
{ {
outsideVertex = pv; outsideVertex = pv;
break; break;

View File

@ -1,13 +1,10 @@
using System; using System;
using DotRecast.Core;
using DotRecast.Core.Numerics; using DotRecast.Core.Numerics;
namespace DotRecast.Detour namespace DotRecast.Detour
{ {
public static class DtUtils public static class DtUtils
{ {
private static readonly float EQUAL_THRESHOLD = RcMath.Sqr(1.0f / 16384.0f);
public static int NextPow2(int v) public static int NextPow2(int v)
{ {
v--; v--;
@ -39,24 +36,6 @@ namespace DotRecast.Detour
return r; return r;
} }
/// Performs a 'sloppy' colocation check of the specified points.
/// @param[in] p0 A point. [(x, y, z)]
/// @param[in] p1 A point. [(x, y, z)]
/// @return True if the points are considered to be at the same location.
///
/// Basically, this function will return true if the specified points are
/// close enough to eachother to be considered colocated.
public static bool VEqual(RcVec3f p0, RcVec3f p1)
{
return VEqual(p0, p1, EQUAL_THRESHOLD);
}
public static bool VEqual(RcVec3f p0, RcVec3f p1, float thresholdSqr)
{
float d = RcVec3f.DistanceSquared(p0, p1);
return d < thresholdSqr;
}
/// Determines if two axis-aligned bounding boxes overlap. /// Determines if two axis-aligned bounding boxes overlap.
/// @param[in] amin Minimum bounds of box A. [(x, y, z)] /// @param[in] amin Minimum bounds of box A. [(x, y, z)]
/// @param[in] amax Maximum bounds of box A. [(x, y, z)] /// @param[in] amax Maximum bounds of box A. [(x, y, z)]
@ -252,7 +231,7 @@ namespace DotRecast.Detour
rmin = rmax = axis.Dot2D(new RcVec3f(poly)); rmin = rmax = axis.Dot2D(new RcVec3f(poly));
for (int i = 1; i < npoly; ++i) for (int i = 1; i < npoly; ++i)
{ {
float d = axis.Dot2D(RcVecUtils.Create(poly, i * 3)); float d = axis.Dot2D(RcVec.Create(poly, i * 3));
rmin = Math.Min(rmin, d); rmin = Math.Min(rmin, d);
rmax = Math.Max(rmax, d); rmax = Math.Max(rmax, d);
} }
@ -309,8 +288,8 @@ namespace DotRecast.Detour
public static float DistancePtSegSqr2D(RcVec3f pt, Span<float> verts, int p, int q, out float t) public static float DistancePtSegSqr2D(RcVec3f pt, Span<float> verts, int p, int q, out float t)
{ {
var vp = RcVecUtils.Create(verts, p); var vp = RcVec.Create(verts, p);
var vq = RcVecUtils.Create(verts, q); var vq = RcVec.Create(verts, q);
return DistancePtSegSqr2D(pt, vp, vq, out t); return DistancePtSegSqr2D(pt, vp, vq, out t);
} }
@ -362,8 +341,8 @@ namespace DotRecast.Detour
RcVec3f vpi = verts[i]; RcVec3f vpi = verts[i];
var edge = RcVec3f.Subtract(vpi, vpj); var edge = RcVec3f.Subtract(vpi, vpj);
var diff = RcVec3f.Subtract(p0v, vpj); var diff = RcVec3f.Subtract(p0v, vpj);
float n = RcVecUtils.Perp2D(edge, diff); float n = RcVec.Perp2D(edge, diff);
float d = RcVecUtils.Perp2D(dir, edge); float d = RcVec.Perp2D(dir, edge);
if (MathF.Abs(d) < EPS) if (MathF.Abs(d) < EPS)
{ {
// S is nearly parallel to this edge // S is nearly parallel to this edge
@ -425,14 +404,14 @@ namespace DotRecast.Detour
RcVec3f u = RcVec3f.Subtract(aq, ap); RcVec3f u = RcVec3f.Subtract(aq, ap);
RcVec3f v = RcVec3f.Subtract(bq, bp); RcVec3f v = RcVec3f.Subtract(bq, bp);
RcVec3f w = RcVec3f.Subtract(ap, bp); RcVec3f w = RcVec3f.Subtract(ap, bp);
float d = RcVecUtils.PerpXZ(u, v); float d = RcVec.PerpXZ(u, v);
if (MathF.Abs(d) < 1e-6f) if (MathF.Abs(d) < 1e-6f)
{ {
return false; return false;
} }
s = RcVecUtils.PerpXZ(v, w) / d; s = RcVec.PerpXZ(v, w) / d;
t = RcVecUtils.PerpXZ(u, w) / d; t = RcVec.PerpXZ(u, w) / d;
return true; return true;
} }

View File

@ -234,7 +234,7 @@ public class CrowdSampleTool : ISampleTool
dd.Vertex(prev.X, prev.Y + 0.1f, prev.Z, DuRGBA(0, 0, 0, (int)(128 * preva))); dd.Vertex(prev.X, prev.Y + 0.1f, prev.Z, DuRGBA(0, 0, 0, (int)(128 * preva)));
dd.Vertex(trail.trail[v], trail.trail[v + 1] + 0.1f, trail.trail[v + 2], DuRGBA(0, 0, 0, (int)(128 * a))); dd.Vertex(trail.trail[v], trail.trail[v + 1] + 0.1f, trail.trail[v + 2], DuRGBA(0, 0, 0, (int)(128 * a)));
preva = a; preva = a;
prev = RcVecUtils.Create(trail.trail, v); prev = RcVec.Create(trail.trail, v);
} }
dd.End(); dd.End();

View File

@ -155,9 +155,9 @@ public static class GizmoRenderer
debugDraw.Begin(DebugDrawPrimitives.TRIS); debugDraw.Begin(DebugDrawPrimitives.TRIS);
for (int i = 0; i < trimesh.triangles.Length; i += 3) for (int i = 0; i < trimesh.triangles.Length; i += 3)
{ {
RcVec3f v0 = RcVecUtils.Create(trimesh.vertices, 3 * trimesh.triangles[i]); RcVec3f v0 = RcVec.Create(trimesh.vertices, 3 * trimesh.triangles[i]);
RcVec3f v1 = RcVecUtils.Create(trimesh.vertices, 3 * trimesh.triangles[i + 1]); RcVec3f v1 = RcVec.Create(trimesh.vertices, 3 * trimesh.triangles[i + 1]);
RcVec3f v2 = RcVecUtils.Create(trimesh.vertices, 3 * trimesh.triangles[i + 2]); RcVec3f v2 = RcVec.Create(trimesh.vertices, 3 * trimesh.triangles[i + 2]);
int col = GetColorByNormal(v0, v1, v2); int col = GetColorByNormal(v0, v1, v2);
debugDraw.Vertex(v0.X, v0.Y, v0.Z, col); debugDraw.Vertex(v0.X, v0.Y, v0.Z, col);
debugDraw.Vertex(v1.X, v1.Y, v1.Z, col); debugDraw.Vertex(v1.X, v1.Y, v1.Z, col);

View File

@ -511,10 +511,10 @@ public class TestNavmeshSampleTool : ISampleTool
} }
RcVec3f delta = RcVec3f.Subtract(s3, s.vmin); RcVec3f delta = RcVec3f.Subtract(s3, s.vmin);
RcVec3f p0 = RcVecUtils.Mad(s.vmin, delta, 0.5f); RcVec3f p0 = RcVec.Mad(s.vmin, delta, 0.5f);
RcVec3f norm = new RcVec3f(delta.Z, 0, -delta.X); RcVec3f norm = new RcVec3f(delta.Z, 0, -delta.X);
norm = RcVec3f.Normalize(norm); norm = RcVec3f.Normalize(norm);
RcVec3f p1 = RcVecUtils.Mad(p0, norm, agentRadius * 0.5f); RcVec3f p1 = RcVec.Mad(p0, norm, agentRadius * 0.5f);
// Skip backfacing segments. // Skip backfacing segments.
if (segmentRefs[j] != 0) if (segmentRefs[j] != 0)
{ {

View File

@ -61,8 +61,8 @@ namespace DotRecast.Recast.Toolset.Geom
bmax = new RcVec3f(vertices); bmax = new RcVec3f(vertices);
for (int i = 1; i < vertices.Length / 3; i++) for (int i = 1; i < vertices.Length / 3; i++)
{ {
bmin = RcVec3f.Min(bmin, RcVecUtils.Create(vertices, i * 3)); bmin = RcVec3f.Min(bmin, RcVec.Create(vertices, i * 3));
bmax = RcVec3f.Max(bmax, RcVecUtils.Create(vertices, i * 3)); bmax = RcVec3f.Max(bmax, RcVec.Create(vertices, i * 3));
} }
_mesh = new RcTriMesh(vertices, faces); _mesh = new RcTriMesh(vertices, faces);
@ -87,9 +87,9 @@ namespace DotRecast.Recast.Toolset.Geom
{ {
for (int i = 0; i < faces.Length; i += 3) for (int i = 0; i < faces.Length; i += 3)
{ {
RcVec3f v0 = RcVecUtils.Create(vertices, faces[i] * 3); RcVec3f v0 = RcVec.Create(vertices, faces[i] * 3);
RcVec3f v1 = RcVecUtils.Create(vertices, faces[i + 1] * 3); RcVec3f v1 = RcVec.Create(vertices, faces[i + 1] * 3);
RcVec3f v2 = RcVecUtils.Create(vertices, faces[i + 2] * 3); RcVec3f v2 = RcVec.Create(vertices, faces[i + 2] * 3);
RcVec3f e0 = v1 - v0; RcVec3f e0 = v1 - v0;
RcVec3f e1 = v2 - v0; RcVec3f e1 = v2 - v0;

View File

@ -116,7 +116,7 @@ namespace DotRecast.Recast.Toolset.Tools
{ {
RcVec3f p = link.startSamples[i].p; RcVec3f p = link.startSamples[i].p;
RcVec3f q = link.endSamples[i].p; RcVec3f q = link.endSamples[i].p;
if (i == 0 || RcVecUtils.Dist2D(prev, p) > agentRadius) if (i == 0 || RcVec.Dist2D(prev, p) > agentRadius)
{ {
geom.AddOffMeshConnection(p, q, agentRadius, false, area, flags); geom.AddOffMeshConnection(p, q, agentRadius, false, area, flags);
prev = p; prev = p;

View File

@ -34,7 +34,7 @@ namespace DotRecast.Recast.Toolset.Tools
RcOffMeshConnection nearestConnection = null; RcOffMeshConnection nearestConnection = null;
foreach (RcOffMeshConnection offMeshCon in geom.GetOffMeshConnections()) foreach (RcOffMeshConnection offMeshCon in geom.GetOffMeshConnections())
{ {
float d = Math.Min(RcVecUtils.DistanceSquared(p, offMeshCon.verts, 0), RcVecUtils.DistanceSquared(p, offMeshCon.verts, 3)); float d = Math.Min(RcVec.DistanceSquared(p, offMeshCon.verts, 0), RcVec.DistanceSquared(p, offMeshCon.verts, 3));
if (d < nearestDist && Math.Sqrt(d) < settings.agentRadius) if (d < nearestDist && Math.Sqrt(d) < settings.agentRadius)
{ {
nearestDist = d; nearestDist = d;

View File

@ -91,7 +91,7 @@ namespace DotRecast.Recast.Toolset.Tools
len = STEP_SIZE / len; len = STEP_SIZE / len;
} }
RcVec3f moveTgt = RcVecUtils.Mad(iterPos, delta, len); RcVec3f moveTgt = RcVec.Mad(iterPos, delta, len);
// Move // Move
navQuery.MoveAlongSurface(pathIterPolys[0], iterPos, moveTgt, filter, out var result, visited, out nvisited, 16); navQuery.MoveAlongSurface(pathIterPolys[0], iterPos, moveTgt, filter, out var result, visited, out nvisited, 16);

View File

@ -81,8 +81,8 @@ namespace DotRecast.Recast.Geom
bmax = new RcVec3f(vertices); bmax = new RcVec3f(vertices);
for (int i = 1; i < vertices.Length / 3; i++) for (int i = 1; i < vertices.Length / 3; i++)
{ {
bmin = RcVec3f.Min(bmin, RcVecUtils.Create(vertices, i * 3)); bmin = RcVec3f.Min(bmin, RcVec.Create(vertices, i * 3));
bmax = RcVec3f.Max(bmax, RcVecUtils.Create(vertices, i * 3)); bmax = RcVec3f.Max(bmax, RcVec.Create(vertices, i * 3));
} }
_mesh = new RcTriMesh(vertices, faces); _mesh = new RcTriMesh(vertices, faces);

View File

@ -460,8 +460,8 @@ namespace DotRecast.Recast
RcVec3f bmax = new RcVec3f(verts); RcVec3f bmax = new RcVec3f(verts);
for (int i = 3; i < verts.Length; i += 3) for (int i = 3; i < verts.Length; i += 3)
{ {
bmin = RcVec3f.Min(bmin, RcVecUtils.Create(verts, i)); bmin = RcVec3f.Min(bmin, RcVec.Create(verts, i));
bmax = RcVec3f.Max(bmax, RcVecUtils.Create(verts, i)); bmax = RcVec3f.Max(bmax, RcVec.Create(verts, i));
} }
bmin.Y = minY; bmin.Y = minY;
@ -752,19 +752,19 @@ namespace DotRecast.Recast
int vertIndexB = vertIndex; int vertIndexB = vertIndex;
int vertIndexC = (vertIndex + 1) % numVerts; int vertIndexC = (vertIndex + 1) % numVerts;
RcVec3f vertA = RcVecUtils.Create(verts, vertIndexA * 3); RcVec3f vertA = RcVec.Create(verts, vertIndexA * 3);
RcVec3f vertB = RcVecUtils.Create(verts, vertIndexB * 3); RcVec3f vertB = RcVec.Create(verts, vertIndexB * 3);
RcVec3f vertC = RcVecUtils.Create(verts, vertIndexC * 3); RcVec3f vertC = RcVec.Create(verts, vertIndexC * 3);
// From A to B on the x/z plane // From A to B on the x/z plane
RcVec3f prevSegmentDir = RcVec3f.Subtract(vertB, vertA); RcVec3f prevSegmentDir = RcVec3f.Subtract(vertB, vertA);
prevSegmentDir.Y = 0; // Squash onto x/z plane prevSegmentDir.Y = 0; // Squash onto x/z plane
prevSegmentDir = RcVecUtils.SafeNormalize(prevSegmentDir); prevSegmentDir = RcVec.SafeNormalize(prevSegmentDir);
// From B to C on the x/z plane // From B to C on the x/z plane
RcVec3f currSegmentDir = RcVec3f.Subtract(vertC, vertB); RcVec3f currSegmentDir = RcVec3f.Subtract(vertC, vertB);
currSegmentDir.Y = 0; // Squash onto x/z plane currSegmentDir.Y = 0; // Squash onto x/z plane
currSegmentDir = RcVecUtils.SafeNormalize(currSegmentDir); currSegmentDir = RcVec.SafeNormalize(currSegmentDir);
// The y component of the cross product of the two normalized segment directions. // The y component of the cross product of the two normalized segment directions.
// The X and Z components of the cross product are both zero because the two // The X and Z components of the cross product are both zero because the two
@ -791,7 +791,7 @@ namespace DotRecast.Recast
bool bevel = cornerMiterSqMag * MITER_LIMIT * MITER_LIMIT < 1.0f; bool bevel = cornerMiterSqMag * MITER_LIMIT * MITER_LIMIT < 1.0f;
// Scale the corner miter so it's proportional to how much the corner should be offset compared to the edges. // Scale the corner miter so it's proportional to how much the corner should be offset compared to the edges.
if (cornerMiterSqMag > RcVecUtils.EPSILON) if (cornerMiterSqMag > RcVec.EPSILON)
{ {
float scale = 1.0f / cornerMiterSqMag; float scale = 1.0f / cornerMiterSqMag;
cornerMiterX *= scale; cornerMiterX *= scale;

View File

@ -176,7 +176,7 @@ namespace DotRecast.Recast
private static void Plane(float[][] planes, int p, float[] v1, float[] v2, float[] vertices, int vert) private static void Plane(float[][] planes, int p, float[] v1, float[] v2, float[] vertices, int vert)
{ {
RcVecUtils.Cross(planes[p], v1, v2); RcVec.Cross(planes[p], v1, v2);
planes[p][3] = planes[p][0] * vertices[vert] + planes[p][1] * vertices[vert + 1] + planes[p][2] * vertices[vert + 2]; planes[p][3] = planes[p][0] * vertices[vert] + planes[p][1] * vertices[vert + 1] + planes[p][2] * vertices[vert + 2];
} }

View File

@ -27,7 +27,7 @@ using DotRecast.Core.Numerics;
namespace DotRecast.Recast namespace DotRecast.Recast
{ {
using static RcRecast; using static RcRecast;
using static RcVecUtils; using static RcVec;
using static EdgeValues; using static EdgeValues;
public static class RcMeshDetails public static class RcMeshDetails
@ -182,9 +182,9 @@ namespace DotRecast.Recast
float dmin = float.MaxValue; float dmin = float.MaxValue;
for (int i = 0; i < ntris; ++i) for (int i = 0; i < ntris; ++i)
{ {
RcVec3f va = RcVecUtils.Create(verts, tris[i * 4 + 0] * 3); RcVec3f va = RcVec.Create(verts, tris[i * 4 + 0] * 3);
RcVec3f vb = RcVecUtils.Create(verts, tris[i * 4 + 1] * 3); RcVec3f vb = RcVec.Create(verts, tris[i * 4 + 1] * 3);
RcVec3f vc = RcVecUtils.Create(verts, tris[i * 4 + 2] * 3); RcVec3f vc = RcVec.Create(verts, tris[i * 4 + 2] * 3);
float d = DistPtTri(p, va, vb, vc); float d = DistPtTri(p, va, vb, vc);
if (d < dmin) if (d < dmin)
{ {
@ -421,9 +421,9 @@ namespace DotRecast.Recast
continue; continue;
} }
RcVec3f vs = RcVecUtils.Create(pts, s * 3); RcVec3f vs = RcVec.Create(pts, s * 3);
RcVec3f vt = RcVecUtils.Create(pts, t * 3); RcVec3f vt = RcVec.Create(pts, t * 3);
RcVec3f vu = RcVecUtils.Create(pts, u * 3); RcVec3f vu = RcVec.Create(pts, u * 3);
if (Cross2(vs, vt, vu) > EPS) if (Cross2(vs, vt, vu) > EPS)
{ {
@ -728,7 +728,7 @@ namespace DotRecast.Recast
for (int i = 0; i < nin; ++i) for (int i = 0; i < nin; ++i)
{ {
RcVecUtils.Copy(verts, i * 3, @in, i * 3); RcVec.Copy(verts, i * 3, @in, i * 3);
} }
edges.Clear(); edges.Clear();
@ -844,7 +844,7 @@ namespace DotRecast.Recast
{ {
for (int k = nidx - 2; k > 0; --k) for (int k = nidx - 2; k > 0; --k)
{ {
RcVecUtils.Copy(verts, nverts * 3, edge, idx[k] * 3); RcVec.Copy(verts, nverts * 3, edge, idx[k] * 3);
hull[nhull++] = nverts; hull[nhull++] = nverts;
nverts++; nverts++;
} }
@ -853,7 +853,7 @@ namespace DotRecast.Recast
{ {
for (int k = 1; k < nidx - 1; ++k) for (int k = 1; k < nidx - 1; ++k)
{ {
RcVecUtils.Copy(verts, nverts * 3, edge, idx[k] * 3); RcVec.Copy(verts, nverts * 3, edge, idx[k] * 3);
hull[nhull++] = nverts; hull[nhull++] = nverts;
nverts++; nverts++;
} }
@ -888,8 +888,8 @@ namespace DotRecast.Recast
RcVec3f bmax = new RcVec3f(@in); RcVec3f bmax = new RcVec3f(@in);
for (int i = 1; i < nin; ++i) for (int i = 1; i < nin; ++i)
{ {
bmin = RcVec3f.Min(bmin, RcVecUtils.Create(@in, i * 3)); bmin = RcVec3f.Min(bmin, RcVec.Create(@in, i * 3));
bmax = RcVec3f.Max(bmax, RcVecUtils.Create(@in, i * 3)); bmax = RcVec3f.Max(bmax, RcVec.Create(@in, i * 3));
} }
int x0 = (int)MathF.Floor(bmin.X / sampleDist); int x0 = (int)MathF.Floor(bmin.X / sampleDist);
@ -1561,7 +1561,7 @@ namespace DotRecast.Recast
for (int k = 0; k < dm.nverts; ++k) for (int k = 0; k < dm.nverts; ++k)
{ {
RcVecUtils.Copy(mesh.verts, mesh.nverts * 3, dm.verts, k * 3); RcVec.Copy(mesh.verts, mesh.nverts * 3, dm.verts, k * 3);
mesh.nverts++; mesh.nverts++;
} }

View File

@ -233,7 +233,7 @@ namespace DotRecast.Recast
inVerts[outVerts1 + poly1Vert * 3 + 0] = inVerts[inVertsOffset + inVertB * 3 + 0] + (inVerts[inVertsOffset + inVertA * 3 + 0] - inVerts[inVertsOffset + inVertB * 3 + 0]) * s; inVerts[outVerts1 + poly1Vert * 3 + 0] = inVerts[inVertsOffset + inVertB * 3 + 0] + (inVerts[inVertsOffset + inVertA * 3 + 0] - inVerts[inVertsOffset + inVertB * 3 + 0]) * s;
inVerts[outVerts1 + poly1Vert * 3 + 1] = inVerts[inVertsOffset + inVertB * 3 + 1] + (inVerts[inVertsOffset + inVertA * 3 + 1] - inVerts[inVertsOffset + inVertB * 3 + 1]) * s; inVerts[outVerts1 + poly1Vert * 3 + 1] = inVerts[inVertsOffset + inVertB * 3 + 1] + (inVerts[inVertsOffset + inVertA * 3 + 1] - inVerts[inVertsOffset + inVertB * 3 + 1]) * s;
inVerts[outVerts1 + poly1Vert * 3 + 2] = inVerts[inVertsOffset + inVertB * 3 + 2] + (inVerts[inVertsOffset + inVertA * 3 + 2] - inVerts[inVertsOffset + inVertB * 3 + 2]) * s; inVerts[outVerts1 + poly1Vert * 3 + 2] = inVerts[inVertsOffset + inVertB * 3 + 2] + (inVerts[inVertsOffset + inVertA * 3 + 2] - inVerts[inVertsOffset + inVertB * 3 + 2]) * s;
RcVecUtils.Copy(inVerts, outVerts2 + poly2Vert * 3, inVerts, outVerts1 + poly1Vert * 3); RcVec.Copy(inVerts, outVerts2 + poly2Vert * 3, inVerts, outVerts1 + poly1Vert * 3);
poly1Vert++; poly1Vert++;
poly2Vert++; poly2Vert++;
@ -241,12 +241,12 @@ namespace DotRecast.Recast
// since these were already added above // since these were already added above
if (inVertAxisDelta[inVertA] > 0) if (inVertAxisDelta[inVertA] > 0)
{ {
RcVecUtils.Copy(inVerts, outVerts1 + poly1Vert * 3, inVerts, inVertsOffset + inVertA * 3); RcVec.Copy(inVerts, outVerts1 + poly1Vert * 3, inVerts, inVertsOffset + inVertA * 3);
poly1Vert++; poly1Vert++;
} }
else if (inVertAxisDelta[inVertA] < 0) else if (inVertAxisDelta[inVertA] < 0)
{ {
RcVecUtils.Copy(inVerts, outVerts2 + poly2Vert * 3, inVerts, inVertsOffset + inVertA * 3); RcVec.Copy(inVerts, outVerts2 + poly2Vert * 3, inVerts, inVertsOffset + inVertA * 3);
poly2Vert++; poly2Vert++;
} }
} }
@ -255,7 +255,7 @@ namespace DotRecast.Recast
// add the i'th point to the right polygon. Addition is done even for points on the dividing line // add the i'th point to the right polygon. Addition is done even for points on the dividing line
if (inVertAxisDelta[inVertA] >= 0) if (inVertAxisDelta[inVertA] >= 0)
{ {
RcVecUtils.Copy(inVerts, outVerts1 + poly1Vert * 3, inVerts, inVertsOffset + inVertA * 3); RcVec.Copy(inVerts, outVerts1 + poly1Vert * 3, inVerts, inVertsOffset + inVertA * 3);
poly1Vert++; poly1Vert++;
if (inVertAxisDelta[inVertA] != 0) if (inVertAxisDelta[inVertA] != 0)
{ {
@ -263,7 +263,7 @@ namespace DotRecast.Recast
} }
} }
RcVecUtils.Copy(inVerts, outVerts2 + poly2Vert * 3, inVerts, inVertsOffset + inVertA * 3); RcVec.Copy(inVerts, outVerts2 + poly2Vert * 3, inVerts, inVertsOffset + inVertA * 3);
poly2Vert++; poly2Vert++;
} }
} }
@ -295,13 +295,13 @@ namespace DotRecast.Recast
int flagMergeThreshold) int flagMergeThreshold)
{ {
// Calculate the bounding box of the triangle. // Calculate the bounding box of the triangle.
RcVec3f triBBMin = RcVecUtils.Create(verts, v0 * 3); RcVec3f triBBMin = RcVec.Create(verts, v0 * 3);
triBBMin = RcVec3f.Min(triBBMin, RcVecUtils.Create(verts, v1 * 3)); triBBMin = RcVec3f.Min(triBBMin, RcVec.Create(verts, v1 * 3));
triBBMin = RcVec3f.Min(triBBMin, RcVecUtils.Create(verts, v2 * 3)); triBBMin = RcVec3f.Min(triBBMin, RcVec.Create(verts, v2 * 3));
RcVec3f triBBMax = RcVecUtils.Create(verts, v0 * 3); RcVec3f triBBMax = RcVec.Create(verts, v0 * 3);
triBBMax = RcVec3f.Max(triBBMax, RcVecUtils.Create(verts, v1 * 3)); triBBMax = RcVec3f.Max(triBBMax, RcVec.Create(verts, v1 * 3));
triBBMax = RcVec3f.Max(triBBMax, RcVecUtils.Create(verts, v2 * 3)); triBBMax = RcVec3f.Max(triBBMax, RcVec.Create(verts, v2 * 3));
// If the triangle does not touch the bounding box of the heightfield, skip the triangle. // If the triangle does not touch the bounding box of the heightfield, skip the triangle.
if (!OverlapBounds(triBBMin, triBBMax, heightfieldBBMin, heightfieldBBMax)) if (!OverlapBounds(triBBMin, triBBMax, heightfieldBBMin, heightfieldBBMax))
@ -328,9 +328,9 @@ namespace DotRecast.Recast
int p1 = inRow + 7 * 3; int p1 = inRow + 7 * 3;
int p2 = p1 + 7 * 3; int p2 = p1 + 7 * 3;
RcVecUtils.Copy(buf, 0, verts, v0 * 3); RcVec.Copy(buf, 0, verts, v0 * 3);
RcVecUtils.Copy(buf, 3, verts, v1 * 3); RcVec.Copy(buf, 3, verts, v1 * 3);
RcVecUtils.Copy(buf, 6, verts, v2 * 3); RcVec.Copy(buf, 6, verts, v2 * 3);
int nvRow; int nvRow;
int nvIn = 3; int nvIn = 3;

View File

@ -193,9 +193,9 @@ namespace DotRecast.Recast
for (int i = 0; i < nt; ++i) for (int i = 0; i < nt; ++i)
{ {
int tri = i * 3; int tri = i * 3;
RcVec3f v0 = RcVecUtils.Create(verts, tris[tri + 0] * 3); RcVec3f v0 = RcVec.Create(verts, tris[tri + 0] * 3);
RcVec3f v1 = RcVecUtils.Create(verts, tris[tri + 1] * 3); RcVec3f v1 = RcVec.Create(verts, tris[tri + 1] * 3);
RcVec3f v2 = RcVecUtils.Create(verts, tris[tri + 2] * 3); RcVec3f v2 = RcVec.Create(verts, tris[tri + 2] * 3);
CalcTriNormal(v0, v1, v2, ref norm); CalcTriNormal(v0, v1, v2, ref norm);
// Check if the face is walkable. // Check if the face is walkable.
if (norm.Y > walkableThr) if (norm.Y > walkableThr)
@ -231,9 +231,9 @@ namespace DotRecast.Recast
for (int i = 0; i < nt; ++i) for (int i = 0; i < nt; ++i)
{ {
int tri = i * 3; int tri = i * 3;
RcVec3f v0 = RcVecUtils.Create(verts, tris[tri + 0] * 3); RcVec3f v0 = RcVec.Create(verts, tris[tri + 0] * 3);
RcVec3f v1 = RcVecUtils.Create(verts, tris[tri + 1] * 3); RcVec3f v1 = RcVec.Create(verts, tris[tri + 1] * 3);
RcVec3f v2 = RcVecUtils.Create(verts, tris[tri + 2] * 3); RcVec3f v2 = RcVec.Create(verts, tris[tri + 2] * 3);
CalcTriNormal(v0, v1, v2, ref norm); CalcTriNormal(v0, v1, v2, ref norm);
// Check if the face is walkable. // Check if the face is walkable.
if (norm.Y <= walkableThr) if (norm.Y <= walkableThr)

View File

@ -54,7 +54,7 @@ public class NavMeshBuilderTest
for (int i = 0; i < 2; i++) for (int i = 0; i < 2; i++)
{ {
Assert.That(RcVecUtils.Create(nmd.verts, 223 * 3 + (i * 3)), Is.EqualTo(nmd.offMeshCons[0].pos[i])); Assert.That(RcVec.Create(nmd.verts, 223 * 3 + (i * 3)), Is.EqualTo(nmd.offMeshCons[0].pos[i]));
} }
Assert.That(nmd.offMeshCons[0].rad, Is.EqualTo(0.1f)); Assert.That(nmd.offMeshCons[0].rad, Is.EqualTo(0.1f));

View File

@ -108,7 +108,7 @@ public class RandomPointTest : AbstractDetourTest
var status = query.FindRandomPointWithinCircle(randomRef, randomPt, radius, filter, f, out var nextRandomRef, out var nextRandomPt); var status = query.FindRandomPointWithinCircle(randomRef, randomPt, radius, filter, f, out var nextRandomRef, out var nextRandomPt);
Assert.That(status.Failed(), Is.False); Assert.That(status.Failed(), Is.False);
float distance = RcVecUtils.Dist2D(randomPt, nextRandomPt); float distance = RcVec.Dist2D(randomPt, nextRandomPt);
Assert.That(distance <= radius, Is.True); Assert.That(distance <= radius, Is.True);
randomRef = nextRandomRef; randomRef = nextRandomRef;