Adding A* Algorythm and carpet roads

This commit is contained in:
Nicolas SANS
2023-04-24 15:49:03 +02:00
parent 75018ee6cd
commit 690e3fbd0b
685 changed files with 134125 additions and 19 deletions

View File

@ -0,0 +1,547 @@
//#define ASTARDEBUG //"BBTree Debug" If enables, some queries to the tree will show debug lines. Turn off multithreading when using this since DrawLine calls cannot be called from a different thread
using System;
using UnityEngine;
namespace Pathfinding {
using Pathfinding.Util;
/// <summary>
/// Axis Aligned Bounding Box Tree.
/// Holds a bounding box tree of triangles.
/// </summary>
public class BBTree : IAstarPooledObject {
/// <summary>Holds all tree nodes</summary>
BBTreeBox[] tree = null;
TriangleMeshNode[] nodeLookup = null;
int count;
int leafNodes;
const int MaximumLeafSize = 4;
public Rect Size {
get {
if (count == 0) {
return new Rect(0, 0, 0, 0);
} else {
var rect = tree[0].rect;
return Rect.MinMaxRect(rect.xmin*Int3.PrecisionFactor, rect.ymin*Int3.PrecisionFactor, rect.xmax*Int3.PrecisionFactor, rect.ymax*Int3.PrecisionFactor);
}
}
}
/// <summary>
/// Clear the tree.
/// Note that references to old nodes will still be intact so the GC cannot immediately collect them.
/// </summary>
public void Clear () {
count = 0;
leafNodes = 0;
if (tree != null) ArrayPool<BBTreeBox>.Release(ref tree);
if (nodeLookup != null) {
// Prevent memory leaks as the pool does not clear the array
for (int i = 0; i < nodeLookup.Length; i++) nodeLookup[i] = null;
ArrayPool<TriangleMeshNode>.Release(ref nodeLookup);
}
tree = ArrayPool<BBTreeBox>.Claim(0);
nodeLookup = ArrayPool<TriangleMeshNode>.Claim(0);
}
void IAstarPooledObject.OnEnterPool () {
Clear();
}
void EnsureCapacity (int c) {
if (c > tree.Length) {
var newArr = ArrayPool<BBTreeBox>.Claim(c);
tree.CopyTo(newArr, 0);
ArrayPool<BBTreeBox>.Release(ref tree);
tree = newArr;
}
}
void EnsureNodeCapacity (int c) {
if (c > nodeLookup.Length) {
var newArr = ArrayPool<TriangleMeshNode>.Claim(c);
nodeLookup.CopyTo(newArr, 0);
ArrayPool<TriangleMeshNode>.Release(ref nodeLookup);
nodeLookup = newArr;
}
}
int GetBox (IntRect rect) {
if (count >= tree.Length) EnsureCapacity(count+1);
tree[count] = new BBTreeBox(rect);
count++;
return count-1;
}
/// <summary>Rebuilds the tree using the specified nodes</summary>
public void RebuildFrom (TriangleMeshNode[] nodes) {
Clear();
if (nodes.Length == 0) return;
// We will use approximately 2N tree nodes
EnsureCapacity(Mathf.CeilToInt(nodes.Length * 2.1f));
// We will use approximately N node references
EnsureNodeCapacity(Mathf.CeilToInt(nodes.Length * 1.1f));
// This will store the order of the nodes while the tree is being built
// It turns out that it is a lot faster to do this than to actually modify
// the nodes and nodeBounds arrays (presumably since that involves shuffling
// around 20 bytes of memory (sizeof(pointer) + sizeof(IntRect)) per node
// instead of 4 bytes (sizeof(int)).
// It also means we don't have to make a copy of the nodes array since
// we do not modify it
var permutation = ArrayPool<int>.Claim(nodes.Length);
for (int i = 0; i < nodes.Length; i++) {
permutation[i] = i;
}
// Precalculate the bounds of the nodes in XZ space.
// It turns out that calculating the bounds is a bottleneck and precalculating
// the bounds makes it around 3 times faster to build a tree
var nodeBounds = ArrayPool<IntRect>.Claim(nodes.Length);
for (int i = 0; i < nodes.Length; i++) {
Int3 v0, v1, v2;
nodes[i].GetVertices(out v0, out v1, out v2);
var rect = new IntRect(v0.x, v0.z, v0.x, v0.z);
rect = rect.ExpandToContain(v1.x, v1.z);
rect = rect.ExpandToContain(v2.x, v2.z);
nodeBounds[i] = rect;
}
RebuildFromInternal(nodes, permutation, nodeBounds, 0, nodes.Length, false);
ArrayPool<int>.Release(ref permutation);
ArrayPool<IntRect>.Release(ref nodeBounds);
}
static int SplitByX (TriangleMeshNode[] nodes, int[] permutation, int from, int to, int divider) {
int mx = to;
for (int i = from; i < mx; i++) {
if (nodes[permutation[i]].position.x > divider) {
mx--;
// Swap items i and mx
var tmp = permutation[mx];
permutation[mx] = permutation[i];
permutation[i] = tmp;
i--;
}
}
return mx;
}
static int SplitByZ (TriangleMeshNode[] nodes, int[] permutation, int from, int to, int divider) {
int mx = to;
for (int i = from; i < mx; i++) {
if (nodes[permutation[i]].position.z > divider) {
mx--;
// Swap items i and mx
var tmp = permutation[mx];
permutation[mx] = permutation[i];
permutation[i] = tmp;
i--;
}
}
return mx;
}
int RebuildFromInternal (TriangleMeshNode[] nodes, int[] permutation, IntRect[] nodeBounds, int from, int to, bool odd) {
var rect = NodeBounds(permutation, nodeBounds, from, to);
int box = GetBox(rect);
if (to - from <= MaximumLeafSize) {
var nodeOffset = tree[box].nodeOffset = leafNodes*MaximumLeafSize;
EnsureNodeCapacity(nodeOffset + MaximumLeafSize);
leafNodes++;
// Assign all nodes to the array. Note that we also need clear unused slots as the array from the pool may contain any information
for (int i = 0; i < MaximumLeafSize; i++) {
nodeLookup[nodeOffset + i] = i < to - from ? nodes[permutation[from + i]] : null;
}
return box;
}
int splitIndex;
if (odd) {
// X
int divider = (rect.xmin + rect.xmax)/2;
splitIndex = SplitByX(nodes, permutation, from, to, divider);
} else {
// Y/Z
int divider = (rect.ymin + rect.ymax)/2;
splitIndex = SplitByZ(nodes, permutation, from, to, divider);
}
if (splitIndex == from || splitIndex == to) {
// All nodes were on one side of the divider
// Try to split along the other axis
if (!odd) {
// X
int divider = (rect.xmin + rect.xmax)/2;
splitIndex = SplitByX(nodes, permutation, from, to, divider);
} else {
// Y/Z
int divider = (rect.ymin + rect.ymax)/2;
splitIndex = SplitByZ(nodes, permutation, from, to, divider);
}
if (splitIndex == from || splitIndex == to) {
// All nodes were on one side of the divider
// Just pick one half
splitIndex = (from+to)/2;
}
}
tree[box].left = RebuildFromInternal(nodes, permutation, nodeBounds, from, splitIndex, !odd);
tree[box].right = RebuildFromInternal(nodes, permutation, nodeBounds, splitIndex, to, !odd);
return box;
}
/// <summary>Calculates the bounding box in XZ space of all nodes between from (inclusive) and to (exclusive)</summary>
static IntRect NodeBounds (int[] permutation, IntRect[] nodeBounds, int from, int to) {
var rect = nodeBounds[permutation[from]];
for (int j = from + 1; j < to; j++) {
var otherRect = nodeBounds[permutation[j]];
// Equivalent to rect = IntRect.Union(rect, otherRect)
// but manually inlining is approximately
// 25% faster when building an entire tree.
// This code is hot when using navmesh cutting.
rect.xmin = Math.Min(rect.xmin, otherRect.xmin);
rect.ymin = Math.Min(rect.ymin, otherRect.ymin);
rect.xmax = Math.Max(rect.xmax, otherRect.xmax);
rect.ymax = Math.Max(rect.ymax, otherRect.ymax);
}
return rect;
}
[System.Diagnostics.Conditional("ASTARDEBUG")]
static void DrawDebugRect (IntRect rect) {
Debug.DrawLine(new Vector3(rect.xmin, 0, rect.ymin), new Vector3(rect.xmax, 0, rect.ymin), Color.white);
Debug.DrawLine(new Vector3(rect.xmin, 0, rect.ymax), new Vector3(rect.xmax, 0, rect.ymax), Color.white);
Debug.DrawLine(new Vector3(rect.xmin, 0, rect.ymin), new Vector3(rect.xmin, 0, rect.ymax), Color.white);
Debug.DrawLine(new Vector3(rect.xmax, 0, rect.ymin), new Vector3(rect.xmax, 0, rect.ymax), Color.white);
}
[System.Diagnostics.Conditional("ASTARDEBUG")]
static void DrawDebugNode (TriangleMeshNode node, float yoffset, Color color) {
Debug.DrawLine((Vector3)node.GetVertex(1) + Vector3.up*yoffset, (Vector3)node.GetVertex(2) + Vector3.up*yoffset, color);
Debug.DrawLine((Vector3)node.GetVertex(0) + Vector3.up*yoffset, (Vector3)node.GetVertex(1) + Vector3.up*yoffset, color);
Debug.DrawLine((Vector3)node.GetVertex(2) + Vector3.up*yoffset, (Vector3)node.GetVertex(0) + Vector3.up*yoffset, color);
}
/// <summary>
/// Queries the tree for the closest node to p constrained by the NNConstraint.
/// Note that this function will only fill in the constrained node.
/// If you want a node not constrained by any NNConstraint, do an additional search with constraint = NNConstraint.None
/// </summary>
public NNInfoInternal QueryClosest (Vector3 p, NNConstraint constraint, out float distance) {
distance = float.PositiveInfinity;
return QueryClosest(p, constraint, ref distance, new NNInfoInternal(null));
}
/// <summary>
/// Queries the tree for the closest node to p constrained by the NNConstraint trying to improve an existing solution.
/// Note that this function will only fill in the constrained node.
/// If you want a node not constrained by any NNConstraint, do an additional search with constraint = NNConstraint.None
///
/// This method will completely ignore any Y-axis differences in positions.
/// </summary>
/// <param name="p">Point to search around</param>
/// <param name="constraint">Optionally set to constrain which nodes to return</param>
/// <param name="distance">The best distance for the previous solution. Will be updated with the best distance
/// after this search. Will be positive infinity if no node could be found.
/// Set to positive infinity if there was no previous solution.</param>
/// <param name="previous">This search will start from the previous NNInfo and improve it if possible.
/// Even if the search fails on this call, the solution will never be worse than previous.
/// Note that the distance parameter need to be configured with the distance for the previous result
/// otherwise it may get overwritten even though it was actually closer.</param>
public NNInfoInternal QueryClosestXZ (Vector3 p, NNConstraint constraint, ref float distance, NNInfoInternal previous) {
var sqrDistance = distance*distance;
var origSqrDistance = sqrDistance;
if (count > 0 && SquaredRectPointDistance(tree[0].rect, p) < sqrDistance) {
SearchBoxClosestXZ(0, p, ref sqrDistance, constraint, ref previous);
// Only update the distance if the squared distance changed as otherwise #distance
// might change due to rounding errors even if no better solution was found
if (sqrDistance < origSqrDistance) distance = Mathf.Sqrt(sqrDistance);
}
return previous;
}
void SearchBoxClosestXZ (int boxi, Vector3 p, ref float closestSqrDist, NNConstraint constraint, ref NNInfoInternal nnInfo) {
BBTreeBox box = tree[boxi];
if (box.IsLeaf) {
var nodes = nodeLookup;
for (int i = 0; i < MaximumLeafSize && nodes[box.nodeOffset+i] != null; i++) {
var node = nodes[box.nodeOffset+i];
// Update the NNInfo
DrawDebugNode(node, 0.2f, Color.red);
if (constraint == null || constraint.Suitable(node)) {
Vector3 closest = node.ClosestPointOnNodeXZ(p);
// XZ squared distance
float dist = (closest.x-p.x)*(closest.x-p.x)+(closest.z-p.z)*(closest.z-p.z);
// There's a theoretical case when the closest point is on the edge of a node which may cause the
// closest point's xz coordinates to not line up perfectly with p's xz coordinates even though they should
// (because floating point errors are annoying). So use a tiny margin to cover most of those cases.
const float fuzziness = 0.000001f;
if (nnInfo.constrainedNode == null || dist < closestSqrDist - fuzziness || (dist <= closestSqrDist + fuzziness && Mathf.Abs(closest.y - p.y) < Mathf.Abs(nnInfo.constClampedPosition.y - p.y))) {
nnInfo.constrainedNode = node;
nnInfo.constClampedPosition = closest;
closestSqrDist = dist;
}
}
}
} else {
DrawDebugRect(box.rect);
int first = box.left, second = box.right;
float firstDist, secondDist;
GetOrderedChildren(ref first, ref second, out firstDist, out secondDist, p);
// Search children (closest box first to improve performance)
if (firstDist <= closestSqrDist) {
SearchBoxClosestXZ(first, p, ref closestSqrDist, constraint, ref nnInfo);
}
if (secondDist <= closestSqrDist) {
SearchBoxClosestXZ(second, p, ref closestSqrDist, constraint, ref nnInfo);
}
}
}
/// <summary>
/// Queries the tree for the closest node to p constrained by the NNConstraint trying to improve an existing solution.
/// Note that this function will only fill in the constrained node.
/// If you want a node not constrained by any NNConstraint, do an additional search with constraint = NNConstraint.None
/// </summary>
/// <param name="p">Point to search around</param>
/// <param name="constraint">Optionally set to constrain which nodes to return</param>
/// <param name="distance">The best distance for the previous solution. Will be updated with the best distance
/// after this search. Will be positive infinity if no node could be found.
/// Set to positive infinity if there was no previous solution.</param>
/// <param name="previous">This search will start from the previous NNInfo and improve it if possible.
/// Even if the search fails on this call, the solution will never be worse than previous.</param>
public NNInfoInternal QueryClosest (Vector3 p, NNConstraint constraint, ref float distance, NNInfoInternal previous) {
var sqrDistance = distance*distance;
var origSqrDistance = sqrDistance;
if (count > 0 && SquaredRectPointDistance(tree[0].rect, p) < sqrDistance) {
SearchBoxClosest(0, p, ref sqrDistance, constraint, ref previous);
// Only update the distance if the squared distance changed as otherwise #distance
// might change due to rounding errors even if no better solution was found
if (sqrDistance < origSqrDistance) distance = Mathf.Sqrt(sqrDistance);
}
return previous;
}
void SearchBoxClosest (int boxi, Vector3 p, ref float closestSqrDist, NNConstraint constraint, ref NNInfoInternal nnInfo) {
BBTreeBox box = tree[boxi];
if (box.IsLeaf) {
var nodes = nodeLookup;
for (int i = 0; i < MaximumLeafSize && nodes[box.nodeOffset+i] != null; i++) {
var node = nodes[box.nodeOffset+i];
Vector3 closest = node.ClosestPointOnNode(p);
float dist = (closest-p).sqrMagnitude;
if (dist < closestSqrDist) {
DrawDebugNode(node, 0.2f, Color.red);
if (constraint == null || constraint.Suitable(node)) {
// Update the NNInfo
nnInfo.constrainedNode = node;
nnInfo.constClampedPosition = closest;
closestSqrDist = dist;
}
} else {
DrawDebugNode(node, 0.0f, Color.blue);
}
}
} else {
DrawDebugRect(box.rect);
int first = box.left, second = box.right;
float firstDist, secondDist;
GetOrderedChildren(ref first, ref second, out firstDist, out secondDist, p);
// Search children (closest box first to improve performance)
if (firstDist < closestSqrDist) {
SearchBoxClosest(first, p, ref closestSqrDist, constraint, ref nnInfo);
}
if (secondDist < closestSqrDist) {
SearchBoxClosest(second, p, ref closestSqrDist, constraint, ref nnInfo);
}
}
}
/// <summary>Orders the box indices first and second by the approximate distance to the point p</summary>
void GetOrderedChildren (ref int first, ref int second, out float firstDist, out float secondDist, Vector3 p) {
firstDist = SquaredRectPointDistance(tree[first].rect, p);
secondDist = SquaredRectPointDistance(tree[second].rect, p);
if (secondDist < firstDist) {
// Swap
var tmp = first;
first = second;
second = tmp;
var tmp2 = firstDist;
firstDist = secondDist;
secondDist = tmp2;
}
}
/// <summary>
/// Searches for a node which contains the specified point.
/// If there are multiple nodes that contain the point any one of them
/// may be returned.
///
/// See: TriangleMeshNode.ContainsPoint
/// </summary>
public TriangleMeshNode QueryInside (Vector3 p, NNConstraint constraint) {
return count != 0 && tree[0].Contains(p) ? SearchBoxInside(0, p, constraint) : null;
}
TriangleMeshNode SearchBoxInside (int boxi, Vector3 p, NNConstraint constraint) {
BBTreeBox box = tree[boxi];
if (box.IsLeaf) {
var nodes = nodeLookup;
for (int i = 0; i < MaximumLeafSize && nodes[box.nodeOffset+i] != null; i++) {
var node = nodes[box.nodeOffset+i];
if (node.ContainsPoint((Int3)p)) {
DrawDebugNode(node, 0.2f, Color.red);
if (constraint == null || constraint.Suitable(node)) {
return node;
}
} else {
DrawDebugNode(node, 0.0f, Color.blue);
}
}
} else {
DrawDebugRect(box.rect);
//Search children
if (tree[box.left].Contains(p)) {
var result = SearchBoxInside(box.left, p, constraint);
if (result != null) return result;
}
if (tree[box.right].Contains(p)) {
var result = SearchBoxInside(box.right, p, constraint);
if (result != null) return result;
}
}
return null;
}
struct BBTreeBox {
public IntRect rect;
public int nodeOffset;
public int left, right;
public bool IsLeaf {
get {
return nodeOffset >= 0;
}
}
public BBTreeBox (IntRect rect) {
nodeOffset = -1;
this.rect = rect;
left = right = -1;
}
public BBTreeBox (int nodeOffset, IntRect rect) {
this.nodeOffset = nodeOffset;
this.rect = rect;
left = right = -1;
}
public bool Contains (Vector3 point) {
var pi = (Int3)point;
return rect.Contains(pi.x, pi.z);
}
}
public void OnDrawGizmos () {
Gizmos.color = new Color(1, 1, 1, 0.5F);
if (count == 0) return;
OnDrawGizmos(0, 0);
}
void OnDrawGizmos (int boxi, int depth) {
BBTreeBox box = tree[boxi];
var min = (Vector3) new Int3(box.rect.xmin, 0, box.rect.ymin);
var max = (Vector3) new Int3(box.rect.xmax, 0, box.rect.ymax);
Vector3 center = (min+max)*0.5F;
Vector3 size = (max-center)*2;
size = new Vector3(size.x, 1, size.z);
center.y += depth * 2;
Gizmos.color = AstarMath.IntToColor(depth, 1f);
Gizmos.DrawCube(center, size);
if (!box.IsLeaf) {
OnDrawGizmos(box.left, depth + 1);
OnDrawGizmos(box.right, depth + 1);
}
}
static bool NodeIntersectsCircle (TriangleMeshNode node, Vector3 p, float radius) {
if (float.IsPositiveInfinity(radius)) return true;
/// <summary>\bug Is not correct on the Y axis</summary>
return (p - node.ClosestPointOnNode(p)).sqrMagnitude < radius*radius;
}
/// <summary>
/// Returns true if p is within radius from r.
/// Correctly handles cases where radius is positive infinity.
/// </summary>
static bool RectIntersectsCircle (IntRect r, Vector3 p, float radius) {
if (float.IsPositiveInfinity(radius)) return true;
Vector3 po = p;
p.x = Math.Max(p.x, r.xmin*Int3.PrecisionFactor);
p.x = Math.Min(p.x, r.xmax*Int3.PrecisionFactor);
p.z = Math.Max(p.z, r.ymin*Int3.PrecisionFactor);
p.z = Math.Min(p.z, r.ymax*Int3.PrecisionFactor);
// XZ squared magnitude comparison
return (p.x-po.x)*(p.x-po.x) + (p.z-po.z)*(p.z-po.z) < radius*radius;
}
/// <summary>Returns distance from p to the rectangle r</summary>
static float SquaredRectPointDistance (IntRect r, Vector3 p) {
Vector3 po = p;
p.x = Math.Max(p.x, r.xmin*Int3.PrecisionFactor);
p.x = Math.Min(p.x, r.xmax*Int3.PrecisionFactor);
p.z = Math.Max(p.z, r.ymin*Int3.PrecisionFactor);
p.z = Math.Min(p.z, r.ymax*Int3.PrecisionFactor);
// XZ squared magnitude comparison
return (p.x-po.x)*(p.x-po.x) + (p.z-po.z)*(p.z-po.z);
}
}
}

View File

@ -0,0 +1,7 @@
fileFormatVersion: 2
guid: 3a20480c673fd40a5bd2a4cc2206dbc4
MonoImporter:
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}

View File

@ -0,0 +1,58 @@
#pragma warning disable 414
using System.Collections.Generic;
using UnityEngine;
namespace Pathfinding {
public enum HeuristicOptimizationMode {
None,
Random,
RandomSpreadOut,
Custom
}
/// <summary>
/// Implements heuristic optimizations.
///
/// See: heuristic-opt
/// See: Game AI Pro - Pathfinding Architecture Optimizations by Steve Rabin and Nathan R. Sturtevant
/// </summary>
[System.Serializable]
public class EuclideanEmbedding {
/// <summary>
/// If heuristic optimization should be used and how to place the pivot points.
/// See: heuristic-opt
/// See: Game AI Pro - Pathfinding Architecture Optimizations by Steve Rabin and Nathan R. Sturtevant
/// </summary>
public HeuristicOptimizationMode mode;
public int seed;
/// <summary>All children of this transform will be used as pivot points</summary>
public Transform pivotPointRoot;
public int spreadOutCount = 1;
[System.NonSerialized]
public bool dirty;
void EnsureCapacity (int index) {
}
public uint GetHeuristic (int nodeIndex1, int nodeIndex2) {
return 0;
}
public void RecalculatePivots () {
}
public void RecalculateCosts () {
dirty = false;
}
public void OnDrawGizmos () {
}
}
}

View File

@ -0,0 +1,8 @@
fileFormatVersion: 2
guid: 3ac3213e3eeb14eef91939f5281682e6
MonoImporter:
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:

View File

@ -0,0 +1,215 @@
using UnityEngine;
namespace Pathfinding.Util {
/// <summary>
/// Transforms to and from world space to a 2D movement plane.
/// The transformation is guaranteed to be purely a rotation
/// so no scale or offset is used. This interface is primarily
/// used to make it easier to write movement scripts which can
/// handle movement both in the XZ plane and in the XY plane.
///
/// See: <see cref="Pathfinding.Util.GraphTransform"/>
/// </summary>
public interface IMovementPlane {
Vector2 ToPlane(Vector3 p);
Vector2 ToPlane(Vector3 p, out float elevation);
Vector3 ToWorld(Vector2 p, float elevation = 0);
}
/// <summary>Generic 3D coordinate transformation</summary>
public interface ITransform {
Vector3 Transform(Vector3 position);
Vector3 InverseTransform(Vector3 position);
}
/// <summary>
/// Defines a transformation from graph space to world space.
/// This is essentially just a simple wrapper around a matrix, but it has several utilities that are useful.
/// </summary>
public class GraphTransform : IMovementPlane, ITransform {
/// <summary>True if this transform is the identity transform (i.e it does not do anything)</summary>
public readonly bool identity;
/// <summary>True if this transform is a pure translation without any scaling or rotation</summary>
public readonly bool onlyTranslational;
readonly bool isXY;
readonly bool isXZ;
readonly Matrix4x4 matrix;
readonly Matrix4x4 inverseMatrix;
readonly Vector3 up;
readonly Vector3 translation;
readonly Int3 i3translation;
readonly Quaternion rotation;
readonly Quaternion inverseRotation;
public static readonly GraphTransform identityTransform = new GraphTransform(Matrix4x4.identity);
public GraphTransform (Matrix4x4 matrix) {
this.matrix = matrix;
inverseMatrix = matrix.inverse;
identity = matrix.isIdentity;
onlyTranslational = MatrixIsTranslational(matrix);
up = matrix.MultiplyVector(Vector3.up).normalized;
translation = matrix.MultiplyPoint3x4(Vector3.zero);
i3translation = (Int3)translation;
// Extract the rotation from the matrix. This is only correct if the matrix has no skew, but we only
// want to use it for the movement plane so as long as the Up axis is parpendicular to the Forward
// axis everything should be ok. In fact the only case in the project when all three axes are not
// perpendicular is when hexagon or isometric grid graphs are used, but in those cases only the
// X and Z axes are not perpendicular.
rotation = Quaternion.LookRotation(TransformVector(Vector3.forward), TransformVector(Vector3.up));
inverseRotation = Quaternion.Inverse(rotation);
// Some short circuiting code for the movement plane calculations
isXY = rotation == Quaternion.Euler(-90, 0, 0);
isXZ = rotation == Quaternion.Euler(0, 0, 0);
}
public Vector3 WorldUpAtGraphPosition (Vector3 point) {
return up;
}
static bool MatrixIsTranslational (Matrix4x4 matrix) {
return matrix.GetColumn(0) == new Vector4(1, 0, 0, 0) && matrix.GetColumn(1) == new Vector4(0, 1, 0, 0) && matrix.GetColumn(2) == new Vector4(0, 0, 1, 0) && matrix.m33 == 1;
}
public Vector3 Transform (Vector3 point) {
if (onlyTranslational) return point + translation;
return matrix.MultiplyPoint3x4(point);
}
public Vector3 TransformVector (Vector3 point) {
if (onlyTranslational) return point;
return matrix.MultiplyVector(point);
}
public void Transform (Int3[] arr) {
if (onlyTranslational) {
for (int i = arr.Length - 1; i >= 0; i--) arr[i] += i3translation;
} else {
for (int i = arr.Length - 1; i >= 0; i--) arr[i] = (Int3)matrix.MultiplyPoint3x4((Vector3)arr[i]);
}
}
public void Transform (Vector3[] arr) {
if (onlyTranslational) {
for (int i = arr.Length - 1; i >= 0; i--) arr[i] += translation;
} else {
for (int i = arr.Length - 1; i >= 0; i--) arr[i] = matrix.MultiplyPoint3x4(arr[i]);
}
}
public Vector3 InverseTransform (Vector3 point) {
if (onlyTranslational) return point - translation;
return inverseMatrix.MultiplyPoint3x4(point);
}
public Int3 InverseTransform (Int3 point) {
if (onlyTranslational) return point - i3translation;
return (Int3)inverseMatrix.MultiplyPoint3x4((Vector3)point);
}
public void InverseTransform (Int3[] arr) {
for (int i = arr.Length - 1; i >= 0; i--) arr[i] = (Int3)inverseMatrix.MultiplyPoint3x4((Vector3)arr[i]);
}
public static GraphTransform operator * (GraphTransform lhs, Matrix4x4 rhs) {
return new GraphTransform(lhs.matrix * rhs);
}
public static GraphTransform operator * (Matrix4x4 lhs, GraphTransform rhs) {
return new GraphTransform(lhs * rhs.matrix);
}
public Bounds Transform (Bounds bounds) {
if (onlyTranslational) return new Bounds(bounds.center + translation, bounds.size);
var corners = ArrayPool<Vector3>.Claim(8);
var extents = bounds.extents;
corners[0] = Transform(bounds.center + new Vector3(extents.x, extents.y, extents.z));
corners[1] = Transform(bounds.center + new Vector3(extents.x, extents.y, -extents.z));
corners[2] = Transform(bounds.center + new Vector3(extents.x, -extents.y, extents.z));
corners[3] = Transform(bounds.center + new Vector3(extents.x, -extents.y, -extents.z));
corners[4] = Transform(bounds.center + new Vector3(-extents.x, extents.y, extents.z));
corners[5] = Transform(bounds.center + new Vector3(-extents.x, extents.y, -extents.z));
corners[6] = Transform(bounds.center + new Vector3(-extents.x, -extents.y, extents.z));
corners[7] = Transform(bounds.center + new Vector3(-extents.x, -extents.y, -extents.z));
var min = corners[0];
var max = corners[0];
for (int i = 1; i < 8; i++) {
min = Vector3.Min(min, corners[i]);
max = Vector3.Max(max, corners[i]);
}
ArrayPool<Vector3>.Release(ref corners);
return new Bounds((min+max)*0.5f, max - min);
}
public Bounds InverseTransform (Bounds bounds) {
if (onlyTranslational) return new Bounds(bounds.center - translation, bounds.size);
var corners = ArrayPool<Vector3>.Claim(8);
var extents = bounds.extents;
corners[0] = InverseTransform(bounds.center + new Vector3(extents.x, extents.y, extents.z));
corners[1] = InverseTransform(bounds.center + new Vector3(extents.x, extents.y, -extents.z));
corners[2] = InverseTransform(bounds.center + new Vector3(extents.x, -extents.y, extents.z));
corners[3] = InverseTransform(bounds.center + new Vector3(extents.x, -extents.y, -extents.z));
corners[4] = InverseTransform(bounds.center + new Vector3(-extents.x, extents.y, extents.z));
corners[5] = InverseTransform(bounds.center + new Vector3(-extents.x, extents.y, -extents.z));
corners[6] = InverseTransform(bounds.center + new Vector3(-extents.x, -extents.y, extents.z));
corners[7] = InverseTransform(bounds.center + new Vector3(-extents.x, -extents.y, -extents.z));
var min = corners[0];
var max = corners[0];
for (int i = 1; i < 8; i++) {
min = Vector3.Min(min, corners[i]);
max = Vector3.Max(max, corners[i]);
}
ArrayPool<Vector3>.Release(ref corners);
return new Bounds((min+max)*0.5f, max - min);
}
#region IMovementPlane implementation
/// <summary>
/// Transforms from world space to the 'ground' plane of the graph.
/// The transformation is purely a rotation so no scale or offset is used.
///
/// For a graph rotated with the rotation (-90, 0, 0) this will transform
/// a coordinate (x,y,z) to (x,y). For a graph with the rotation (0,0,0)
/// this will tranform a coordinate (x,y,z) to (x,z). More generally for
/// a graph with a quaternion rotation R this will transform a vector V
/// to R * V (i.e rotate the vector V using the rotation R).
/// </summary>
Vector2 IMovementPlane.ToPlane (Vector3 point) {
// These special cases cover most graph orientations used in practice.
// Having them here improves performance in those cases by a factor of
// 2.5 without impacting the generic case in any significant way.
if (isXY) return new Vector2(point.x, point.y);
if (!isXZ) point = inverseRotation * point;
return new Vector2(point.x, point.z);
}
/// <summary>
/// Transforms from world space to the 'ground' plane of the graph.
/// The transformation is purely a rotation so no scale or offset is used.
/// </summary>
Vector2 IMovementPlane.ToPlane (Vector3 point, out float elevation) {
if (!isXZ) point = inverseRotation * point;
elevation = point.y;
return new Vector2(point.x, point.z);
}
/// <summary>
/// Transforms from the 'ground' plane of the graph to world space.
/// The transformation is purely a rotation so no scale or offset is used.
/// </summary>
Vector3 IMovementPlane.ToWorld (Vector2 point, float elevation) {
return rotation * new Vector3(point.x, elevation, point.y);
}
#endregion
}
}

View File

@ -0,0 +1,12 @@
fileFormatVersion: 2
guid: f9d3961465175430a84fd52d1bd31b05
timeCreated: 1474479722
licenseType: Pro
MonoImporter:
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

View File

@ -0,0 +1,192 @@
using System.Collections.Generic;
namespace Pathfinding.Util {
/// <summary>
/// Holds a lookup datastructure to quickly find objects inside rectangles.
/// Objects of type T occupy an integer rectangle in the grid and they can be
/// moved efficiently. You can query for all objects that touch a specified
/// rectangle that runs in O(m*k+r) time where m is the number of objects that
/// the query returns, k is the average number of cells that an object
/// occupies and r is the area of the rectangle query.
///
/// All objects must be contained within a rectangle with one point at the origin
/// (inclusive) and one at <see cref="size"/> (exclusive) that is specified in the constructor.
/// </summary>
public class GridLookup<T> where T : class {
Int2 size;
Item[] cells;
/// <summary>
/// Linked list of all items.
/// Note that the first item in the list is a dummy item and does not contain any data.
/// </summary>
Root all = new Root();
Dictionary<T, Root> rootLookup = new Dictionary<T, Root>();
Stack<Item> itemPool = new Stack<Item>();
public GridLookup (Int2 size) {
this.size = size;
cells = new Item[size.x*size.y];
for (int i = 0; i < cells.Length; i++) cells[i] = new Item();
}
internal class Item {
public Root root;
public Item prev, next;
}
public class Root {
/// <summary>Underlying object</summary>
public T obj;
/// <summary>Next item in the linked list of all roots</summary>
public Root next;
/// <summary>Previous item in the linked list of all roots</summary>
internal Root prev;
internal IntRect previousBounds = new IntRect(0, 0, -1, -1);
/// <summary>References to an item in each grid cell that this object is contained inside</summary>
internal List<Item> items = new List<Item>();
internal bool flag;
}
/// <summary>Linked list of all items</summary>
public Root AllItems {
get {
return all.next;
}
}
public void Clear () {
rootLookup.Clear();
all.next = null;
foreach (var item in cells) item.next = null;
}
public Root GetRoot (T item) {
Root root;
rootLookup.TryGetValue(item, out root);
return root;
}
/// <summary>
/// Add an object to the lookup data structure.
/// Returns: A handle which can be used for Move operations
/// </summary>
public Root Add (T item, IntRect bounds) {
var root = new Root {
obj = item,
prev = all,
next = all.next
};
all.next = root;
if (root.next != null) root.next.prev = root;
rootLookup.Add(item, root);
Move(item, bounds);
return root;
}
/// <summary>Removes an item from the lookup data structure</summary>
public void Remove (T item) {
Root root;
if (!rootLookup.TryGetValue(item, out root)) {
return;
}
// Make the item occupy no cells at all
Move(item, new IntRect(0, 0, -1, -1));
rootLookup.Remove(item);
root.prev.next = root.next;
if (root.next != null) root.next.prev = root.prev;
}
/// <summary>Move an object to occupy a new set of cells</summary>
public void Move (T item, IntRect bounds) {
Root root;
if (!rootLookup.TryGetValue(item, out root)) {
throw new System.ArgumentException("The item has not been added to this object");
}
var prev = root.previousBounds;
if (prev == bounds) return;
// Remove all
for (int i = 0; i < root.items.Count; i++) {
Item ob = root.items[i];
ob.prev.next = ob.next;
if (ob.next != null) ob.next.prev = ob.prev;
}
root.previousBounds = bounds;
int reusedItems = 0;
for (int z = bounds.ymin; z <= bounds.ymax; z++) {
for (int x = bounds.xmin; x <= bounds.xmax; x++) {
Item ob;
if (reusedItems < root.items.Count) {
ob = root.items[reusedItems];
} else {
ob = itemPool.Count > 0 ? itemPool.Pop() : new Item();
ob.root = root;
root.items.Add(ob);
}
reusedItems++;
ob.prev = cells[x + z*size.x];
ob.next = ob.prev.next;
ob.prev.next = ob;
if (ob.next != null) ob.next.prev = ob;
}
}
for (int i = root.items.Count-1; i >= reusedItems; i--) {
Item ob = root.items[i];
ob.root = null;
ob.next = null;
ob.prev = null;
root.items.RemoveAt(i);
itemPool.Push(ob);
}
}
/// <summary>
/// Returns all objects of a specific type inside the cells marked by the rectangle.
/// Note: For better memory usage, consider pooling the list using Pathfinding.Util.ListPool after you are done with it
/// </summary>
public List<U> QueryRect<U>(IntRect r) where U : class, T {
List<U> result = Pathfinding.Util.ListPool<U>.Claim();
// Loop through tiles and check which objects are inside them
for (int z = r.ymin; z <= r.ymax; z++) {
var zs = z*size.x;
for (int x = r.xmin; x <= r.xmax; x++) {
Item c = cells[x + zs];
// Note, first item is a dummy, so it is ignored
while (c.next != null) {
c = c.next;
var obj = c.root.obj as U;
if (!c.root.flag && obj != null) {
c.root.flag = true;
result.Add(obj);
}
}
}
}
// Reset flags
for (int z = r.ymin; z <= r.ymax; z++) {
var zs = z*size.x;
for (int x = r.xmin; x <= r.xmax; x++) {
Item c = cells[x + zs];
while (c.next != null) {
c = c.next;
c.root.flag = false;
}
}
}
return result;
}
}
}

View File

@ -0,0 +1,12 @@
fileFormatVersion: 2
guid: 7b09e5cbe5d4644c2b4ed9eed14cc13a
timeCreated: 1475417043
licenseType: Pro
MonoImporter:
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

View File

@ -0,0 +1,4 @@
// This file has been removed from the project. Since UnityPackages cannot
// delete files, only replace them, this message is left here to prevent old
// files from causing compiler errors

View File

@ -0,0 +1,7 @@
fileFormatVersion: 2
guid: b56789f958bf1496ba91f7e2b4147166
MonoImporter:
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}

View File

@ -0,0 +1,76 @@
namespace Pathfinding {
using Pathfinding.Util;
using UnityEngine;
public class NavmeshTile : INavmeshHolder {
/// <summary>Tile triangles</summary>
public int[] tris;
/// <summary>Tile vertices</summary>
public Int3[] verts;
/// <summary>Tile vertices in graph space</summary>
public Int3[] vertsInGraphSpace;
/// <summary>Tile X Coordinate</summary>
public int x;
/// <summary>Tile Z Coordinate</summary>
public int z;
/// <summary>
/// Width, in tile coordinates.
/// Warning: Widths other than 1 are not supported. This is mainly here for possible future features.
/// </summary>
public int w;
/// <summary>
/// Depth, in tile coordinates.
/// Warning: Depths other than 1 are not supported. This is mainly here for possible future features.
/// </summary>
public int d;
/// <summary>All nodes in the tile</summary>
public TriangleMeshNode[] nodes;
/// <summary>Bounding Box Tree for node lookups</summary>
public BBTree bbTree;
/// <summary>Temporary flag used for batching</summary>
public bool flag;
public NavmeshBase graph;
#region INavmeshHolder implementation
public void GetTileCoordinates (int tileIndex, out int x, out int z) {
x = this.x;
z = this.z;
}
public int GetVertexArrayIndex (int index) {
return index & NavmeshBase.VertexIndexMask;
}
/// <summary>Get a specific vertex in the tile</summary>
public Int3 GetVertex (int index) {
int idx = index & NavmeshBase.VertexIndexMask;
return verts[idx];
}
public Int3 GetVertexInGraphSpace (int index) {
return vertsInGraphSpace[index & NavmeshBase.VertexIndexMask];
}
/// <summary>Transforms coordinates from graph space to world space</summary>
public GraphTransform transform { get { return graph.transform; } }
#endregion
public void GetNodes (System.Action<GraphNode> action) {
if (nodes == null) return;
for (int i = 0; i < nodes.Length; i++) action(nodes[i]);
}
}
}

View File

@ -0,0 +1,12 @@
fileFormatVersion: 2
guid: 7408cbadf2e744d22853a92b15abede1
timeCreated: 1474405146
licenseType: Pro
MonoImporter:
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

View File

@ -0,0 +1,243 @@
/// <summary>
/// This is a simple utility class for importing obj files into a Unity mesh at runtime.
/// This version of ObjImporter first reads through the entire file, getting a count of how large
/// the final arrays will be, and then uses standard arrays for everything (as opposed to ArrayLists
/// or any other fancy things).
/// \author el anónimo at the UnifyCommunity wiki (at least he seems to have created the page)
/// </summary>
using UnityEngine;
using System.Collections.Generic;
using System.IO;
#if NETFX_CORE && !UNITY_EDITOR
//using MarkerMetro.Unity.WinLegacy.IO;
#endif
namespace Pathfinding {
public class ObjImporter {
private struct meshStruct {
public Vector3[] vertices;
public Vector3[] normals;
public Vector2[] uv;
public int[] triangles;
public Vector3[] faceData;
public string fileName;
}
// Use this for initialization
public static Mesh ImportFile (string filePath) {
#if NETFX_CORE
throw new System.NotSupportedException("Method not available on this platform");
#else
if (!File.Exists(filePath)) {
Debug.LogError("No file was found at '"+filePath+"'");
return null;
}
meshStruct newMesh = createMeshStruct(filePath);
populateMeshStruct(ref newMesh);
Vector3[] newVerts = new Vector3[newMesh.faceData.Length];
Vector2[] newUVs = new Vector2[newMesh.faceData.Length];
Vector3[] newNormals = new Vector3[newMesh.faceData.Length];
int i = 0;
/* The following foreach loops through the facedata and assigns the appropriate vertex, uv, or normal
* for the appropriate Unity mesh array.
*/
foreach (Vector3 v in newMesh.faceData) {
newVerts[i] = newMesh.vertices[(int)v.x - 1];
if (v.y >= 1)
newUVs[i] = newMesh.uv[(int)v.y - 1];
if (v.z >= 1)
newNormals[i] = newMesh.normals[(int)v.z - 1];
i++;
}
Mesh mesh = new Mesh();
mesh.vertices = newVerts;
mesh.uv = newUVs;
mesh.normals = newNormals;
mesh.triangles = newMesh.triangles;
mesh.RecalculateBounds();
//mesh.Optimize();
return mesh;
#endif
}
private static meshStruct createMeshStruct (string filename) {
#if NETFX_CORE
throw new System.NotSupportedException("Method not available on this platform");
#else
int triangles = 0;
int vertices = 0;
int vt = 0;
int vn = 0;
int face = 0;
meshStruct mesh = new meshStruct();
mesh.fileName = filename;
StreamReader stream = File.OpenText(filename);
string entireText = stream.ReadToEnd();
stream.Dispose();
using (StringReader reader = new StringReader(entireText))
{
string currentText = reader.ReadLine();
char[] splitIdentifier = { ' ' };
string[] brokenString;
while (currentText != null) {
if (!currentText.StartsWith("f ") && !currentText.StartsWith("v ") && !currentText.StartsWith("vt ")
&& !currentText.StartsWith("vn ")) {
currentText = reader.ReadLine();
if (currentText != null) {
currentText = currentText.Replace(" ", " ");
}
} else {
currentText = currentText.Trim(); //Trim the current line
brokenString = currentText.Split(splitIdentifier, 50); //Split the line into an array, separating the original line by blank spaces
switch (brokenString[0]) {
case "v":
vertices++;
break;
case "vt":
vt++;
break;
case "vn":
vn++;
break;
case "f":
face = face + brokenString.Length - 1;
triangles = triangles + 3 * (brokenString.Length - 2); /*brokenString.Length is 3 or greater since a face must have at least
* 3 vertices. For each additional vertice, there is an additional
* triangle in the mesh (hence this formula).*/
break;
}
currentText = reader.ReadLine();
if (currentText != null) {
currentText = currentText.Replace(" ", " ");
}
}
}
}
mesh.triangles = new int[triangles];
mesh.vertices = new Vector3[vertices];
mesh.uv = new Vector2[vt];
mesh.normals = new Vector3[vn];
mesh.faceData = new Vector3[face];
return mesh;
#endif
}
private static void populateMeshStruct (ref meshStruct mesh) {
#if NETFX_CORE
throw new System.NotSupportedException("Method not available on this platform");
#else
StreamReader stream = File.OpenText(mesh.fileName);
string entireText = stream.ReadToEnd();
stream.Close();
using (StringReader reader = new StringReader(entireText))
{
string currentText = reader.ReadLine();
char[] splitIdentifier = { ' ' };
char[] splitIdentifier2 = { '/' };
string[] brokenString;
string[] brokenBrokenString;
int f = 0;
int f2 = 0;
int v = 0;
int vn = 0;
int vt = 0;
int vt1 = 0;
int vt2 = 0;
while (currentText != null) {
if (!currentText.StartsWith("f ") && !currentText.StartsWith("v ") && !currentText.StartsWith("vt ") &&
!currentText.StartsWith("vn ") && !currentText.StartsWith("g ") && !currentText.StartsWith("usemtl ") &&
!currentText.StartsWith("mtllib ") && !currentText.StartsWith("vt1 ") && !currentText.StartsWith("vt2 ") &&
!currentText.StartsWith("vc ") && !currentText.StartsWith("usemap ")) {
currentText = reader.ReadLine();
if (currentText != null) {
currentText = currentText.Replace(" ", " ");
}
} else {
currentText = currentText.Trim();
brokenString = currentText.Split(splitIdentifier, 50);
switch (brokenString[0]) {
case "g":
break;
case "usemtl":
break;
case "usemap":
break;
case "mtllib":
break;
case "v":
mesh.vertices[v] = new Vector3(System.Convert.ToSingle(brokenString[1]), System.Convert.ToSingle(brokenString[2]),
System.Convert.ToSingle(brokenString[3]));
v++;
break;
case "vt":
mesh.uv[vt] = new Vector2(System.Convert.ToSingle(brokenString[1]), System.Convert.ToSingle(brokenString[2]));
vt++;
break;
case "vt1":
mesh.uv[vt1] = new Vector2(System.Convert.ToSingle(brokenString[1]), System.Convert.ToSingle(brokenString[2]));
vt1++;
break;
case "vt2":
mesh.uv[vt2] = new Vector2(System.Convert.ToSingle(brokenString[1]), System.Convert.ToSingle(brokenString[2]));
vt2++;
break;
case "vn":
mesh.normals[vn] = new Vector3(System.Convert.ToSingle(brokenString[1]), System.Convert.ToSingle(brokenString[2]),
System.Convert.ToSingle(brokenString[3]));
vn++;
break;
case "vc":
break;
case "f":
int j = 1;
List<int> intArray = new List<int>();
while (j < brokenString.Length && ("" + brokenString[j]).Length > 0) {
Vector3 temp = new Vector3();
brokenBrokenString = brokenString[j].Split(splitIdentifier2, 3); //Separate the face into individual components (vert, uv, normal)
temp.x = System.Convert.ToInt32(brokenBrokenString[0]);
if (brokenBrokenString.Length > 1) { //Some .obj files skip UV and normal
if (brokenBrokenString[1] != "") { //Some .obj files skip the uv and not the normal
temp.y = System.Convert.ToInt32(brokenBrokenString[1]);
}
temp.z = System.Convert.ToInt32(brokenBrokenString[2]);
}
j++;
mesh.faceData[f2] = temp;
intArray.Add(f2);
f2++;
}
j = 1;
while (j + 2 < brokenString.Length) { //Create triangles out of the face data. There will generally be more than 1 triangle per face.
mesh.triangles[f] = intArray[0];
f++;
mesh.triangles[f] = intArray[j];
f++;
mesh.triangles[f] = intArray[j+1];
f++;
j++;
}
break;
}
currentText = reader.ReadLine();
if (currentText != null) {
currentText = currentText.Replace(" ", " "); //Some .obj files insert double spaces, this removes them.
}
}
}
}
#endif
}
}
}

View File

@ -0,0 +1,7 @@
fileFormatVersion: 2
guid: a4ed1c6c3af454395b428ad955994366
MonoImporter:
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}

View File

@ -0,0 +1,309 @@
using System.Collections.Generic;
namespace Pathfinding {
using Pathfinding.Util;
/// <summary>
/// Represents a collection of GraphNodes.
/// It allows for fast lookups of the closest node to a point.
///
/// See: https://en.wikipedia.org/wiki/K-d_tree
/// </summary>
public class PointKDTree {
// TODO: Make constant
public const int LeafSize = 10;
public const int LeafArraySize = LeafSize*2 + 1;
Node[] tree = new Node[16];
int numNodes = 0;
readonly List<GraphNode> largeList = new List<GraphNode>();
readonly Stack<GraphNode[]> arrayCache = new Stack<GraphNode[]>();
static readonly IComparer<GraphNode>[] comparers = new IComparer<GraphNode>[] { new CompareX(), new CompareY(), new CompareZ() };
struct Node {
/// <summary>Nodes in this leaf node (null if not a leaf node)</summary>
public GraphNode[] data;
/// <summary>Split point along the <see cref="splitAxis"/> if not a leaf node</summary>
public int split;
/// <summary>Number of non-null entries in <see cref="data"/></summary>
public ushort count;
/// <summary>Axis to split along if not a leaf node (x=0, y=1, z=2)</summary>
public byte splitAxis;
}
// Pretty ugly with one class for each axis, but it has been verified to make the tree around 5% faster
class CompareX : IComparer<GraphNode> {
public int Compare (GraphNode lhs, GraphNode rhs) { return lhs.position.x.CompareTo(rhs.position.x); }
}
class CompareY : IComparer<GraphNode> {
public int Compare (GraphNode lhs, GraphNode rhs) { return lhs.position.y.CompareTo(rhs.position.y); }
}
class CompareZ : IComparer<GraphNode> {
public int Compare (GraphNode lhs, GraphNode rhs) { return lhs.position.z.CompareTo(rhs.position.z); }
}
public PointKDTree() {
tree[1] = new Node { data = GetOrCreateList() };
}
/// <summary>Add the node to the tree</summary>
public void Add (GraphNode node) {
numNodes++;
Add(node, 1);
}
/// <summary>Rebuild the tree starting with all nodes in the array between index start (inclusive) and end (exclusive)</summary>
public void Rebuild (GraphNode[] nodes, int start, int end) {
if (start < 0 || end < start || end > nodes.Length)
throw new System.ArgumentException();
for (int i = 0; i < tree.Length; i++) {
var data = tree[i].data;
if (data != null) {
for (int j = 0; j < LeafArraySize; j++) data[j] = null;
arrayCache.Push(data);
tree[i].data = null;
}
}
numNodes = end - start;
Build(1, new List<GraphNode>(nodes), start, end);
}
GraphNode[] GetOrCreateList () {
// Note, the lists will never become larger than this initial capacity, so possibly they should be replaced by arrays
return arrayCache.Count > 0 ? arrayCache.Pop() : new GraphNode[LeafArraySize];
}
int Size (int index) {
return tree[index].data != null ? tree[index].count : Size(2 * index) + Size(2 * index + 1);
}
void CollectAndClear (int index, List<GraphNode> buffer) {
var nodes = tree[index].data;
var count = tree[index].count;
if (nodes != null) {
tree[index] = new Node();
for (int i = 0; i < count; i++) {
buffer.Add(nodes[i]);
nodes[i] = null;
}
arrayCache.Push(nodes);
} else {
CollectAndClear(index*2, buffer);
CollectAndClear(index*2 + 1, buffer);
}
}
static int MaxAllowedSize (int numNodes, int depth) {
// Allow a node to be 2.5 times as full as it should ideally be
// but do not allow it to contain more than 3/4ths of the total number of nodes
// (important to make sure nodes near the top of the tree also get rebalanced).
// A node should ideally contain numNodes/(2^depth) nodes below it (^ is exponentiation, not xor)
return System.Math.Min(((5 * numNodes) / 2) >> depth, (3 * numNodes) / 4);
}
void Rebalance (int index) {
CollectAndClear(index, largeList);
Build(index, largeList, 0, largeList.Count);
largeList.ClearFast();
}
void EnsureSize (int index) {
if (index >= tree.Length) {
var newLeaves = new Node[System.Math.Max(index + 1, tree.Length*2)];
tree.CopyTo(newLeaves, 0);
tree = newLeaves;
}
}
void Build (int index, List<GraphNode> nodes, int start, int end) {
EnsureSize(index);
if (end - start <= LeafSize) {
var leafData = tree[index].data = GetOrCreateList();
tree[index].count = (ushort)(end - start);
for (int i = start; i < end; i++)
leafData[i - start] = nodes[i];
} else {
Int3 mn, mx;
mn = mx = nodes[start].position;
for (int i = start; i < end; i++) {
var p = nodes[i].position;
mn = new Int3(System.Math.Min(mn.x, p.x), System.Math.Min(mn.y, p.y), System.Math.Min(mn.z, p.z));
mx = new Int3(System.Math.Max(mx.x, p.x), System.Math.Max(mx.y, p.y), System.Math.Max(mx.z, p.z));
}
Int3 diff = mx - mn;
var axis = diff.x > diff.y ? (diff.x > diff.z ? 0 : 2) : (diff.y > diff.z ? 1 : 2);
nodes.Sort(start, end - start, comparers[axis]);
int mid = (start+end)/2;
tree[index].split = (nodes[mid-1].position[axis] + nodes[mid].position[axis] + 1)/2;
tree[index].splitAxis = (byte)axis;
Build(index*2 + 0, nodes, start, mid);
Build(index*2 + 1, nodes, mid, end);
}
}
void Add (GraphNode point, int index, int depth = 0) {
// Move down in the tree until the leaf node is found that this point is inside of
while (tree[index].data == null) {
index = 2 * index + (point.position[tree[index].splitAxis] < tree[index].split ? 0 : 1);
depth++;
}
// Add the point to the leaf node
tree[index].data[tree[index].count++] = point;
// Check if the leaf node is large enough that we need to do some rebalancing
if (tree[index].count >= LeafArraySize) {
int levelsUp = 0;
// Search upwards for nodes that are too large and should be rebalanced
// Rebalance the node above the node that had a too large size so that it can
// move children over to the sibling
while (depth - levelsUp > 0 && Size(index >> levelsUp) > MaxAllowedSize(numNodes, depth-levelsUp)) {
levelsUp++;
}
Rebalance(index >> levelsUp);
}
}
/// <summary>Closest node to the point which satisfies the constraint</summary>
public GraphNode GetNearest (Int3 point, NNConstraint constraint) {
GraphNode best = null;
long bestSqrDist = long.MaxValue;
GetNearestInternal(1, point, constraint, ref best, ref bestSqrDist);
return best;
}
void GetNearestInternal (int index, Int3 point, NNConstraint constraint, ref GraphNode best, ref long bestSqrDist) {
var data = tree[index].data;
if (data != null) {
for (int i = tree[index].count - 1; i >= 0; i--) {
var dist = (data[i].position - point).sqrMagnitudeLong;
if (dist < bestSqrDist && (constraint == null || constraint.Suitable(data[i]))) {
bestSqrDist = dist;
best = data[i];
}
}
} else {
var dist = (long)(point[tree[index].splitAxis] - tree[index].split);
var childIndex = 2 * index + (dist < 0 ? 0 : 1);
GetNearestInternal(childIndex, point, constraint, ref best, ref bestSqrDist);
// Try the other one if it is possible to find a valid node on the other side
if (dist*dist < bestSqrDist) {
// childIndex ^ 1 will flip the last bit, so if childIndex is odd, then childIndex ^ 1 will be even
GetNearestInternal(childIndex ^ 0x1, point, constraint, ref best, ref bestSqrDist);
}
}
}
/// <summary>Closest node to the point which satisfies the constraint</summary>
public GraphNode GetNearestConnection (Int3 point, NNConstraint constraint, long maximumSqrConnectionLength) {
GraphNode best = null;
long bestSqrDist = long.MaxValue;
// Given a found point at a distance of r world units
// then any node that has a connection on which a closer point lies must have a squared distance lower than
// d^2 < (maximumConnectionLength/2)^2 + r^2
// Note: (x/2)^2 = (x^2)/4
// Note: (x+3)/4 to round up
long offset = (maximumSqrConnectionLength+3)/4;
GetNearestConnectionInternal(1, point, constraint, ref best, ref bestSqrDist, offset);
return best;
}
void GetNearestConnectionInternal (int index, Int3 point, NNConstraint constraint, ref GraphNode best, ref long bestSqrDist, long distanceThresholdOffset) {
var data = tree[index].data;
if (data != null) {
var pointv3 = (UnityEngine.Vector3)point;
for (int i = tree[index].count - 1; i >= 0; i--) {
var dist = (data[i].position - point).sqrMagnitudeLong;
// Note: the subtraction is important. If we used an addition on the RHS instead the result might overflow as bestSqrDist starts as long.MaxValue
if (dist - distanceThresholdOffset < bestSqrDist && (constraint == null || constraint.Suitable(data[i]))) {
// This node may contains the closest connection
// Check all connections
var conns = (data[i] as PointNode).connections;
if (conns != null) {
var nodePos = (UnityEngine.Vector3)data[i].position;
for (int j = 0; j < conns.Length; j++) {
// Find the closest point on the connection, but only on this node's side of the connection
// This ensures that we will find the closest node with the closest connection.
var connectionMidpoint = ((UnityEngine.Vector3)conns[j].node.position + nodePos) * 0.5f;
float sqrConnectionDistance = VectorMath.SqrDistancePointSegment(nodePos, connectionMidpoint, pointv3);
// Convert to Int3 space
long sqrConnectionDistanceInt = (long)(sqrConnectionDistance*Int3.FloatPrecision*Int3.FloatPrecision);
if (sqrConnectionDistanceInt < bestSqrDist) {
bestSqrDist = sqrConnectionDistanceInt;
best = data[i];
}
}
}
// Also check if the node itself is close enough.
// This is important if the node has no connections at all.
if (dist < bestSqrDist) {
bestSqrDist = dist;
best = data[i];
}
}
}
} else {
var dist = (long)(point[tree[index].splitAxis] - tree[index].split);
var childIndex = 2 * index + (dist < 0 ? 0 : 1);
GetNearestConnectionInternal(childIndex, point, constraint, ref best, ref bestSqrDist, distanceThresholdOffset);
// Try the other one if it is possible to find a valid node on the other side
// Note: the subtraction is important. If we used an addition on the RHS instead the result might overflow as bestSqrDist starts as long.MaxValue
if (dist*dist - distanceThresholdOffset < bestSqrDist) {
// childIndex ^ 1 will flip the last bit, so if childIndex is odd, then childIndex ^ 1 will be even
GetNearestConnectionInternal(childIndex ^ 0x1, point, constraint, ref best, ref bestSqrDist, distanceThresholdOffset);
}
}
}
/// <summary>Add all nodes within a squared distance of the point to the buffer.</summary>
/// <param name="point">Nodes around this point will be added to the buffer.</param>
/// <param name="sqrRadius">squared maximum distance in Int3 space. If you are converting from world space you will need to multiply by Int3.Precision:
/// <code> var sqrRadius = (worldSpaceRadius * Int3.Precision) * (worldSpaceRadius * Int3.Precision); </code></param>
/// <param name="buffer">All nodes will be added to this list.</param>
public void GetInRange (Int3 point, long sqrRadius, List<GraphNode> buffer) {
GetInRangeInternal(1, point, sqrRadius, buffer);
}
void GetInRangeInternal (int index, Int3 point, long sqrRadius, List<GraphNode> buffer) {
var data = tree[index].data;
if (data != null) {
for (int i = tree[index].count - 1; i >= 0; i--) {
var dist = (data[i].position - point).sqrMagnitudeLong;
if (dist < sqrRadius) {
buffer.Add(data[i]);
}
}
} else {
var dist = (long)(point[tree[index].splitAxis] - tree[index].split);
// Pick the first child to enter based on which side of the splitting line the point is
var childIndex = 2 * index + (dist < 0 ? 0 : 1);
GetInRangeInternal(childIndex, point, sqrRadius, buffer);
// Try the other one if it is possible to find a valid node on the other side
if (dist*dist < sqrRadius) {
// childIndex ^ 1 will flip the last bit, so if childIndex is odd, then childIndex ^ 1 will be even
GetInRangeInternal(childIndex ^ 0x1, point, sqrRadius, buffer);
}
}
}
}
}

View File

@ -0,0 +1,12 @@
fileFormatVersion: 2
guid: 4aef007a0dd474c20872caa35fbbc8a7
timeCreated: 1462714767
licenseType: Pro
MonoImporter:
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant: