原文出处:寻路算法研究(一)寻路算法基础

寻路问题建模

属性导航网格格子路点
实现复杂度
内存和计算开销
表达精确性
优点精确表征世界,内存和计算开销适中容易实现,动态修改简单实现简单,内存和计算开销低
缺点复杂,难以实现和修改,建网格耗时耗内存内存和计算开销大,可能需要额外平滑,不太适合3D地图需要人工参与,灵活性低,不考虑实际底层地图
适用场景地图大,精确度要求高地图中等,不太大,内存充足路径固定,不考虑真实地形影响

基础寻路算法

深度和广度优先

DFS

DFS(node, goal):
if node is goal:
    return path to node
mark node as visited

for each neighbor in neighbors(node):
    if neighbor is not visited:
        path = DFS(neighbor, goal)
        if path is not None:
            return path
return None

BFS

BFS(start, goal):
create a queue Q
enqueue start onto Q
mark start as visited

while Q is not empty:
    node = dequeue Q
    if node is goal:
        return path to node
    for each neighbor in neighbors(node):
        if neighbor is not visited:
            mark neighbor as visited
            enqueue neighbor onto Q
return None

Dijkstra算法

Dijkstra(graph, start, goal):
    create a priority queue Q
    for each node in graph:
        dist[node] = infinity
        previous[node] = undefined
    dist[start] = 0
    Q.insert(start, dist[start])

    while Q is not empty:
        node = Q.extract_min()
        if node is goal:
            return reconstruct_path(previous, goal)
        for each neighbor in neighbors(node):
            alt = dist[node] + cost(node, neighbor)
            if alt < dist[neighbor]:
                dist[neighbor] = alt
                previous[neighbor] = node
                Q.decrease_key(neighbor, alt)
    return None

reconstruct_path(previous, goal):
    path = []
    while goal is not undefined:
        path.prepend(goal)
        goal = previous[goal]
    return path

Floyd算法(Floyd-Warshall算法)

FloydWarshall(graph):
n = number of nodes in graph
dist = array[n][n]

for i from 1 to n:
    for j from 1 to n:
        if i == j:
            dist[i][j] = 0
        else if (i, j) in graph:
            dist[i][j] = weight of edge (i, j)
        else:
            dist[i][j] = infinity

for k from 1 to n:
    for i from 1 to n:
        for j from 1 to n:
            if dist[i][j] > dist[i][k] + dist[k][j]:
                dist[i][j] = dist[i][k] + dist[k][j]
return dist

Bellman-Ford算法

BellmanFord(graph, source):
    n = number of nodes in graph
    dist = array[n]
    parent = array[n]
    ## Step 1: Initialize distances from source to all other nodes as infinity
    for i from 1 to n:
        dist[i] = infinity
        parent[i] = undefined
    dist[source] = 0

    ## Step 2: Relax all edges |V| - 1 times
    for i from 1 to n-1:
        for each edge (u, v) in graph:
            if dist[u] + weight(u, v) < dist[v]:
                dist[v] = dist[u] + weight(u, v)
                parent[v] = u

    ## Step 3: Check for negative-weight cycles
    for each edge (u, v) in graph:
        if dist[u] + weight(u, v) < dist[v]:
            print("Graph contains a negative-weight cycle")
            return None
    return dist, parent

reconstruct_path(parent, target):
    path = []
    while target is not undefined:
        path.append(target)
        target = parent[target]
    path.reverse()
    return path

SPFA算法(Shortest Path Faster Algorithm)

SPFA(graph, source):
n = number of nodes in graph
dist = array[n]
inQueue = array[n]

for i from 1 to n:
    dist[i] = infinity
    inQueue[i] = false
dist[source] = 0
queue = [source]
inQueue[source] = true

while queue is not empty:
    u = queue.pop(0)
    inQueue[u] = false
    for each neighbor v of u:
        if dist[u] + weight(u, v) < dist[v]:
            dist[v] = dist[u] + weight(u, v)
            if not inQueue[v]:
                queue.append(v)
                inQueue[v] = true
return dist

贪婪最佳优先搜索

GreedyBestFirstSearch(start, goal, heuristic):
create a priority queue Q
Q.insert(start, heuristic(start, goal))
mark start as visited

while Q is not empty:
    node = Q.extract_min()
    if node is goal:
        return path to node
    for each neighbor in neighbors(node):
        if neighbor is not visited:
            mark neighbor as visited
            Q.insert(neighbor, heuristic(neighbor, goal))
return None

总结

算法时间复杂度空间复杂度优点缺点适用场景
深度优先搜索 (DFS)O(V + E)O(V)实现简单,内存使用低可能会陷入死循环,不保证找到最短路径小规模图,解决迷宫问题,图遍历
广度优先搜索 (BFS)O(V + E)O(V)能找到无权图中的最短路径内存使用较高短路径搜索,图遍历,树的层次遍历
Dijkstra算法O(V^2) 或 O(E + V log V)(使用优先队列)O(V^2) 或 O(V)(使用优先队列)适用于无负权边的图,可以找到最短路径无法处理带负权边的图带权图的最短路径问题,网络路由
Floyd-Warshall算法O(V^3)O(V^2)能解决所有节点对的最短路径问题,可处理负权边时间和空间复杂度高稠密图,解决所有节点对的最短路径问题
Bellman-Ford算法O(V * E)O(V)能处理带负权边的图,检测负权环时间复杂度较高,效率低于Dijkstra单源最短路径,带负权边的图
SPFA算法平均O(V)~O(E)O(V)优化了Bellman-Ford算法,效率高于Bellman-Ford可能会进入死循环,需要检测负权环单源最短路径,带负权边的图
贪婪最佳优先搜索O(E)O(V)通常能较快找到解决方案不保证最短路径路径规划,启发式搜索

A*算法及其改进算法

A*

AStar(graph, start, goal, heuristic):
    create an open set (priority queue) Q
    create a closed set
    g_score = {node: infinity for node in graph}
    f_score = {node: infinity for node in graph}
    g_score[start] = 0
    f_score[start] = heuristic(start, goal)
    Q.insert(start, f_score[start])

    while Q is not empty:
        current = Q.extract_min()
        if current is goal:
            return reconstruct_path(came_from, current)
        closed_set.add(current)
        for neighbor in neighbors(current):
            if neighbor in closed_set:
                continue
            tentative_g_score = g_score[current] + cost(current, neighbor)
            if tentative_g_score < g_score[neighbor]:
                came_from[neighbor] = current
                g_score[neighbor] = tentative_g_score
                f_score[neighbor] = g_score[neighbor] + heuristic(neighbor, goal)
                if neighbor not in Q:
                    Q.insert(neighbor, f_score[neighbor])
    return None

reconstruct_path(came_from, current):
    path = []
    while current in came_from:
        path.append(current)
        current = came_from[current]
    path.reverse()
    return path

JPS和JPS+算法

JPS算法

JPS(start, goal, grid):
   openSet = priority queue
   closedSet = set
   gScore = dictionary with default value infinity
   fScore = dictionary with default value infinity
   parent = dictionary
   gScore[start] = 0
   fScore[start] = heuristic(start, goal)
   openSet.insert(start, fScore[start])

   while openSet is not empty:
       current = openSet.extract_min()
       if current == goal:
           return reconstruct_path(parent, current)
       closedSet.add(current)
       for neighbor in jump_neighbors(current, goal, grid):
           if neighbor in closedSet:
               continue
           tentative_gScore = gScore[current] + distance(current, neighbor)
           if tentative_gScore < gScore[neighbor]:
               gScore[neighbor] = tentative_gScore
               parent[neighbor] = current
               fScore[neighbor] = gScore[neighbor] + heuristic(neighbor, goal)
               if neighbor not in openSet:
                   openSet.insert(neighbor, fScore[neighbor])
   return None

jump_neighbors(current, goal, grid):
   neighbors = []
   for direction in possible_directions:
       jumpPoint = jump(current, direction, goal, grid)
       if jumpPoint is not None:
           neighbors.append(jumpPoint)
   return neighbors

jump(current, direction, goal, grid):
   next = current + direction
   if not in_bounds(next, grid) or is_obstacle(next, grid):
       return None
   if next == goal:
       return next
   if forced_neighbors(next, direction, grid):
       return next
   if direction is diagonal:
       if jump(next, (direction[0], 0), goal, grid) is not None or \\
          jump(next, (0, direction[1]), goal, grid) is not None:
           return next
   return jump(next, direction, goal, grid)

forced_neighbors(node, direction, grid):
   ## Implement detection of forced neighbors
   return True or False

reconstruct_path(parent, current):
   path = []
   while current in parent:
       path.append(current)
       current = parent[current]
   path.reverse()
   return path

JPS+算法

JPSPlus(start, goal, grid):
   preprocessed_grid = preprocess_grid(grid)
   openSet = priority queue
   closedSet = set
   gScore = dictionary with default value infinity
   fScore = dictionary with default value infinity
   parent = dictionary
   gScore[start] = 0
   fScore[start] = heuristic(start, goal)
   openSet.insert(start, fScore[start])

   while openSet is not empty:
       current = openSet.extract_min()
       if current == goal:
           return reconstruct_path(parent, current)
       closedSet.add(current)
       for neighbor in jump_neighbors_plus(current, goal, preprocessed_grid):
           if neighbor in closedSet:
               continue
           tentative_gScore = gScore[current] + distance(current, neighbor)
           if tentative_gScore < gScore[neighbor]:
               gScore[neighbor] = tentative_gScore
               parent[neighbor] = current
               fScore[neighbor] = gScore[neighbor] + heuristic(neighbor, goal)
               if neighbor not in openSet:
                   openSet.insert(neighbor, fScore[neighbor])
   return None

preprocess_grid(grid):
   ## Implement preprocessing to compute jump points
   return preprocessed_grid

jump_neighbors_plus(current, goal, preprocessed_grid):
   ## Use precomputed jump points from preprocessed_grid
   neighbors = preprocessed_grid[current]
   return neighbors

reconstruct_path(parent, current):
   path = []
   while current in parent:
       path.append(current)
       current = parent[current]
   path.reverse()
   return path

B*算法

BStar(graph, start, goal, heuristic):
    openSet = priority queue
    closedSet = set
    gScore = dictionary with default value infinity
    fScore = dictionary with default value infinity
    bScore = dictionary with default value 0
    parent = dictionary
    gScore[start] = 0
    fScore[start] = heuristic(start, goal) + bScore[start]
    openSet.insert(start, fScore[start])
    while openSet is not empty:
        current = openSet.extract_min()
        if current == goal:
            return reconstruct_path(parent, current)
        closedSet.add(current)
        for neighbor in neighbors(current, graph):
            if neighbor in closedSet:
                continue
            tentative_gScore = gScore[current] + distance(current, neighbor)
            tentativeFScore = tentative_gScore + heuristic(neighbor, goal) + bScore[neighbor]
            if tentative_gScore < gScore[neighbor]:
                gScore[neighbor] = tentative_gScore
                fScore[neighbor] = tentativeFScore
                parent[neighbor] = current
                if neighbor not in openSet:
                    openSet.insert(neighbor, fScore[neighbor])
                else:
                    openSet.update(neighbor, fScore[neighbor])
        ## Update the boundary function b(n)
        update_bScore(bScore, current, graph)
    return None

def update_bScore(bScore, current, graph):
    ## Implement the logic to update bScore based on current node and graph
    pass

def reconstruct_path(parent, current):
    path = []
    while current in parent:
        path.append(current)
        current = parent[current]
    path.reverse()
    return path

Theta*算法

ThetaStar(graph, start, goal, heuristic):
   openSet = priority queue
   closedSet = set
   gScore = dictionary with default value infinity
   fScore = dictionary with default value infinity
   parent = dictionary
   gScore[start] = 0
   fScore[start] = heuristic(start, goal)
   openSet.insert(start, fScore[start])
   while openSet is not empty:
       current = openSet.extract_min()
       if current == goal:
           return reconstruct_path(parent, current)
       closedSet.add(current)
       for neighbor in neighbors(current):
           if neighbor in closedSet:
               continue
           tentative_gScore = gScore[current] + distance(current, neighbor)
           if has_line_of_sight(parent[current], neighbor):
               new_gScore = gScore[parent[current]] + distance(parent[current], neighbor)
               if new_gScore < gScore[neighbor]:
                   gScore[neighbor] = new_gScore
                   parent[neighbor] = parent[current]
                   fScore[neighbor] = gScore[neighbor] + heuristic(neighbor, goal)
                   if neighbor not in openSet:
                       openSet.insert(neighbor, fScore[neighbor])
           else:
               if tentative_gScore < gScore[neighbor]:
                   gScore[neighbor] = tentative_gScore
                   parent[neighbor] = current
                   fScore[neighbor] = gScore[neighbor] + heuristic(neighbor, goal)
                   if neighbor not in openSet:
                       openSet.insert(neighbor, fScore[neighbor])
   return None

reconstruct_path(parent, current):
   path = []
   while current in parent:
       path.append(current)
       current = parent[current]
   path.reverse()
   return path

has_line_of_sight(node1, node2):
   ## Implement line-of-sight check
   return True or False

IDA*算法

总结

算法时间复杂度空间复杂度优点缺点适用场景
A*O(E)O(V)启发式搜索,效率高,能找到最优路径需要合理的启发式函数,可能受启发式函数影响较大需要快速且最优路径规划的场景
JPSO(E)O(V)大幅减少A*需要评估的节点数量,提高搜索效率仅适用于网格图,需实现复杂的跳点检测算法网格图的路径规划,启发式搜索
JPS+O(E)O(V) + 预处理时间和空间基于JPS进一步优化,通过预处理减少实时计算开销,提高速度需要预处理地图,适用范围较局限大规模网格图的路径规划,启发式搜索
B*O(E)O(V)通过动态调整界限函数,提高搜索效率;避免冤枉路需要额外维护和计算界限函数,实现复杂度较高需要高效路径规划的复杂环境,如游戏AI、机器人导航等
Theta*O(E)O(V)将A*的启发式搜索与线性插值相结合,能找到更短且平滑的路径实现较为复杂,可能需要更多的计算资源需要平滑路径且高效的路径规划场景,如机器人导航
IDA*O(b^d)O(d)空间效率高,适合内存受限环境,能找到最优路径时间效率较低,多次迭代增加计算开销内存受限但需要最优路径的场景,如嵌入式系统、机器人导航

A*算法优化思路

预先计算好每一条路径

Hierarchical and Dynamic Pathfinding

Hierarchical Pathfinding(层次化寻路)

Dynamic Pathfinding(动态寻路)

预分配所需的内存空间

高估或者更好的启发函数

参考文章


原文出处:寻路算法研究(二)RecastNavigation

导语 一文介绍RecastNavigation的基本背景,模块组成,Recast和Detour两大模块实现原理,Offmesh、动态阻碍、Detourcrowd等特性。

NavMesh引入

早期导航网格-Meadow Map

MeadowMappingRecastNavigation
可行走区域生成方式手工绘制基于体素构建可行走区域,最后生成边缘
凸多边形构建二分法耳切法
路径改善局部贪心拉绳算法

当代导航网格方案

Havok AI与NavPower

Recast Navigation

Recast中体素的存储

体素的存储主要有两种方式,稀疏八叉树和高度场,由于后者更适合地形的表示与处理,Recast采取了后者。

稀疏八叉树SVO

高度场Span

两者对比

特性稀疏八叉树(SVO)高度场Span
数据结构八叉树体素数组与索引数组
内存效率高(仅存储有内容的空间)中(基于高度场,较为紧凑)
查询效率取决于树的高度高(数组索引操作)
适用场景三维体素数据存储,稀疏数据场景地形表示与高度场数据处理
实现复杂度较高
存储方式多层次的节点与指针结构体素数组 span_arr 和索引数组 cell_arr
数据查询递归查找数组索引快速定位
存储空间利用率较高
示例应用三维游戏场景、复杂模型存储地形编辑器、地形生成和渲染
优势内存占用小、适合稀疏数据存储查找效率高、适合地形数据处理
劣势实现复杂度高、查询可能较慢(递归)不适合高维稀疏数据、需要额外索引数组

RecastNavigation概览

总体介绍

代理属性

导航网格生成方式

大体过程

Recast

根据输入几何边界确定栅格体素格网的大小
rcCalcGridSize

对输入几何体素化
rcAllocHeightfield
rcCreateHeightfield rcCreateHeight字段
rcMarkWalkableTriangles
rcRasterizeTriangles

清理体素数据并过滤掉不适合步行的区域
rcFilterLowHangingWalkableObstacles
rcFilterLedgeSpans
rcFilterWalkableLowHeightSpans

将体素数据合并为更紧凑的表示形式
rcAllocCompactHeightfield
rcAllocCompactHeight字段
rcBuildCompactHeightfield
rcBuildCompactHeight字段

进一步优化体素表示
rcErodeWalkableArea
rcBuildDistanceField
rcBuildRegions rcBuild区域

根据体素数据对导航网格面进行三角测量
rcAllocContourSet
rcBuildContours
rcAllocPolyMesh
rcBuildPolyMesh

使用在运行时有用的其他元数据打包网格
rcAllocPolyMeshDetail
rcBuildPolyMeshDetail

rcFreeHeightField
rcFreeCompactHeightfield rcFreeCompactHeight字段
rcFreeContourSet
StepTime(ms)Percentage
Rasterize0.2435.9%
Build Compact0.046.6%
Filter Border0.046.6%
Filter Walkable0.010.8%
Erode Area0.046.6%
Median Area0.000.0%
Mark Box Area0.000.0%
Mark Convex Area0.000.0%
Mark Cylinder Area0.000.0%
Build Distance Field - Distance0.045.5%
Build Distance Field - Blur0.011.7%
Build Regions - Expand0.034.4%
Build Regions - Find Basins0.011.4%
Build Regions - Filter0.011.7%
Build Layers0.011.7%
Build Contours - Trace0.023.5%
Build Contours - Simplify0.012.1%
Build PolyMesh0.011.4%
Build PolyMesh Detail0.068.5%
Merge PolyMeshes0.000.0%
Merge PolyMesh Details0.000.0%
TOTAL0.5888.4%
* 在recastdemo右侧栏目中有着控制各个阶段的参数信息

Detour

Recast具体原理

加载场景数据

struct rcConfig
{
    int width; // 场景中x向的cell个数
    int height; // 场景中z向的cell个数
    int tileSize; // tile正方形的边长
    int borderSize; // 指定距离四周边界多远的区域不用生成导航数据,缩小需要生成的区域
    float cs; // cell size
    float ch; // cell height
    float bmin[3]; // 场景包围盒坐标
    float bmax[3]; // 场景包围盒坐标
    float walkableSlopeAngle; // 最大可行走坡度
    int walkableHeight; // 最小可行走通过的高度
    int walkableClimb; // 最大的可攀爬高度
    int walkableRadius; // agent的半径
    int maxEdgeLen; // 最终导航网格中多边形周长的最大值,限定多边形的大小
    float maxSimplificationError; // 最终导航网格中多边形周长的最大值,限定多边形的大小    
    int minRegionArea; // 独立岛屿region的最小cell数目
    int mergeRegionArea; // span数目小于此值的region都将被合并
    int maxVertsPerPoly; // 多边形的最多顶点数目
};
const float* verts;///输入的顶点集合
const int* tris;///输入的三角形集合
int ntris;///输入的三角形个数

///三角形在xz平面投影的包围盒
struct BoundsItem
{
    float bmin[2];
    float bmax[2];
    int i;///由于会对包围盒按坐标排序,id记录了这个包围盒对应的输入三角形的id
};

///BVH的节点
struct rcChunkyTriMeshNode
{
    float bmin[2];///包含区域内所有三角形的包围盒
    float bmax[2];
    int i;///i为正表示是叶子节点;i为负表示是非叶子节点,大小等于在数组内的覆盖范围
    int n;///节点内包含的三角形个数
};

///一棵BVH树
struct rcChunkyTriMesh
{
    rcChunkyTriMeshNode* nodes;///根节点
    int nnodes;///节点个数
    int* tris;///按区域划分排序后的三角形集合
    int ntris;///三角形个数
    int maxTrisPerChunk;///叶子节点最多包含的三角形数
}

将输入的三角面体素化

过滤不可行走三角形面

void rcMarkWalkableTriangles(rcContext* ctx, const float walkableSlopeAngle,
                             const float* verts, int nv,
                             const int* tris, int nt,
                             unsigned char* areas)
{
    rcIgnoreUnused(ctx);
    rcIgnoreUnused(nv);
    const float walkableThr = cosf(walkableSlopeAngle/180.0f*RC_PI);
    float norm[3];
    for (int i = 0; i < nt; ++i)
    {
        const int* tri = &tris[i*3];
        calcTriNormal(&verts[tri[0]*3], &verts[tri[1]*3], &verts[tri[2]*3], norm);
        // Check if the face is walkable.
        if (norm[1] > walkableThr)
            areas[i] = RC_WALKABLE_AREA;
    }
}

体素化三角面

建立高度场

struct rcSpan
{
    unsigned int smin : RC_SPAN_HEIGHT_BITS; ///< The lower limit of the span. [Limit: < #smax]
    unsigned int smax : RC_SPAN_HEIGHT_BITS; ///< The upper limit of the span. [Limit: <= #RC_SPAN_MAX_HEIGHT]
    unsigned int area : 6;                   ///< The area id assigned to the span.
    rcSpan* next;                            ///< The next span higher up in column.
};
struct rcHeightfield
{
    rcHeightfield();
    ~rcHeightfield();

    int width;          ///< The width of the heightfield. (Along the x-axis in cell units.)
    int height;         ///< The height of the heightfield. (Along the z-axis in cell units.)
    float bmin[3];      ///< The minimum bounds in world space. [(x, y, z)]
    float bmax[3];      ///< The maximum bounds in world space. [(x, y, z)]
    float cs;           ///< The size of each cell. (On the xz-plane.)
    float ch;           ///< The height of each cell. (The minimum increment along the y-axis.)
    rcSpan** spans;     ///< Heightfield of spans (width*height).
    rcSpanPool* pools;  ///< Linked list of span pools.
    rcSpan* freelist;   ///< The next free span.

private:
    // Explicitly-disabled copy constructor and copy assignment operator.
    rcHeightfield(const rcHeightfield&);
    rcHeightfield& operator=(const rcHeightfield&);
};

过滤不可行走表面

划分可行走表面为 Region

高度场转换为紧缩高度场(rcBuildCompactHeightfield

/// Represents a span of unobstructed space within a compact heightfield.
struct rcCompactSpan
{
    unsigned short y;            ///< The lower extent of the span. (Measured from the heightfield's base.)
    unsigned short reg;            ///< The id of the region the span belongs to. (Or zero if not in a region.)
    unsigned int con : 24;        ///< Packed neighbor connection data.    与 Neighbor Span 的连通性,这里 24bit,每 6 bit 一个方向()
    unsigned int h : 8;            ///< The height of the span.  (Measured from #y.)
};
/// A compact, static heightfield representing unobstructed space.
/// @ingroup recast
struct rcCompactHeightfield
{
    // some define 
    float bmin[3];                ///< The minimum bounds in world space. [(x, y, z)]
    float bmax[3];                ///< The maximum bounds in world space. [(x, y, z)]
    float cs;                    ///< The size of each cell. (On the xz-plane.)
    float ch;                    ///< The height of each cell. (The minimum increment along the y-axis.)
    rcCompactCell* cells;        ///< Array of cells. [Size: #width*#height]                          Cell 的合集,这里采用一维数组表示
    rcCompactSpan* spans;        ///< Array of spans. [Size: #spanCount]                                 所有数组的合集,这里采用一维数组表示
    unsigned short* dist;        ///< Array containing border distance data. [Size: #spanCount]       记录距离场
    unsigned char* areas;        ///< Array containing area id data. [Size: #spanCount]               记录区域是否可行走,或者草地山地等情况
};

/// Provides information on the content of a cell column in a compact heightfield. 
struct rcCompactCell
{
    unsigned int index : 24;    ///< Index to the first span in the column. XZ 平面下的坐标,参考右图                     
    unsigned int count : 8;        ///< Number of spans in the column. 8 位,理论上不会超过 256 个 Span                          
};

裁减区域边缘(rcErodeWalkableArea

区域划分算法

- 关于area id,recast默认情况下只有2种area id,可行走和不可行走,RecastDemo提供了一种功能,在demo左侧的工具栏目中可以利用create convex volumns来创建不同的区域。

划分区域,构建区域轮廓顶点集合

合并区域Region

获取Region轮廓顶点集

简化轮廓顶点集

// 一条轮廓线段
struct rcContour
{
    int* verts;            //简化后轮廓顶点数组
    int nverts;        //简化后顶点数目
    int* rverts;        //原始顶点数组
    int nrverts;        //原始顶点数目
    unsigned short reg;    //拾取轮廓的起始CompactSpan对应Region
    unsigned char area;//拾取轮廓的起始CompactSpan对应area
};

struct rcContourSet
{
    rcContour* conts;    //轮廓数组
    int nconts;        //轮廓数组
    float maxError;    //简化时的最大距离
};

将多边形转换为需要的凸多边形

三角剖分

合并三角形

struct rcPolyMesh
{
    unsigned short* verts;    // 所有的多边形顶点信息
        int nvp;        // 一个多边形中的最多顶点个数
    unsigned short* regs;    // 每个多边形对应的region id
    unsigned char* areas;    // 每个多边形对应的area
    int nverts;        // 顶点总数
    int npolys;        // 多边形总数
    int maxpolys;        // 耳割后的初始的三角形个数
    unsigned short* polys;    // 多边形顶点index及邻居多边形index. [Length: #maxpolys * 2 * #nvp]
};

对凸多边形的高度进行修正

获取高度补丁与轮廓高度修正

多边形内部高度修正

Detour具体原理

找出点所在多边形()

struct dtMeshTile
{
    unsigned int salt;            // 标记当前Tile是否有变更
    dtMeshHeader* header;            // 继续Tile的整体信息
    dtPoly* polys;                // 所有的多边形信息
    float* verts;                // 所有的顶点信息
    dtLink* links;                // 多边形间的连接信息数组,每个多边形对应一个dtLink*,dtLink*是一个单向链表,存储了该多边形的所有连接信息
    dtPolyDetail* detailMeshes;        // 细节网格数据
    float* detailVerts;                    // 细节网格顶点
    unsigned char* detailTris;            // 细节网格三角形
    dtBVNode* bvTree;                       // 多边形对应的BV树
    dtMeshTile* next;                // 下一个tile
};
struct dtPoly
{
    unsigned int firstLink;
    unsigned short verts[DT_VERTS_PER_POLYGON]; //多边形节点索引 从dtMeshTile::verts中取元素
    unsigned short neis[DT_VERTS_PER_POLYGON]; //每条边对应的邻居
    unsigned short flags; // 用户定义标记,不同类型flag对应不同的寻路成本
    unsigned char vertCount; // 多边形数量
    unsigned char areaAndtype; // 对应type和area 高2bit表示type 低6bit表示area
};
* dtBVNode叶子节点的i表示poly id,而非叶子节点则表示右边子节点的跨度
struct dtBVNode
{
    unsigned short bmin[3];            // 该节点包含的多边形的AABB包围盒下边界
    unsigned short bmax[3];            // 该节点包含的多边形的AABB包围盒上边界
    int i;                    // 表示Poly id或者右边子节点的跨度
};

使用A*算法求出多边形序列路径

struct dtNode
{
    float pos[3];                                ///< Position of the node.
    float cost;                                    ///< Cost from previous node to current node.
    float total;                                ///< Cost up to the node.
    unsigned int pidx : DT_NODE_PARENT_BITS;    ///< Index to parent node.
    unsigned int state : DT_NODE_STATE_BITS;    ///< extra state information. A polyRef can have multiple nodes with different extra info. see DT_MAX_STATES_PER_NODE
    unsigned int flags : 3;                        ///< Node flags. A combination of dtNodeFlags.
    dtPolyRef id;                                ///< Polygon ref the node corresponds to.
};

使用拉绳算法(漏斗算法)平滑路径

TempObstacles障碍实现原理

//TempObstacles的大致运作流程
Preprocess
for each tile
- rasterize static triangles
- find walkable cells
- mark areas
- store compressed heighfield

At Run Time
for a changed tile
- uncompressed heighfield
- mark obstacles
- build regions
- build contours
- build poly mesh
- build detail mesh
- store navmesh

DetourCrowd

局部转向和动态避让

局部转向

动态避让(Dynamic Avoidance)

代理添加和配置

// 创建 DetourCrowd 对象
dtCrowd* crowd = dtAllocCrowd();
// 初始化 DetourCrowd
crowd->init(maxAgents, maxAgentRadius, navMesh);
// 配置代理参数
dtCrowdAgentParams ap;
memset(&ap, 0, sizeof(ap));
ap.radius = agentRadius;
ap.height = agentHeight;
ap.maxAcceleration = maxAcceleration;
ap.maxSpeed = maxSpeed;
// 添加代理到 DetourCrowd
int agentId = crowd->addAgent(startPosition, &ap);
// 设置代理目标
crowd->requestMoveTarget(agentId, targetPosition);
// 在每帧更新代理位置和速度
crowd->update(deltaTime, nullptr);

DetourCrowd与RVO的对比

特性DetourCrowdRVO(ReciprocalVelocityObstacles)
实现方式基于导航网格的路径规划和局部避障基于速度障碍理论的局部避障
路径规划使用 A* 算法和路径走廊进行全局路径规划和优化不进行全局路径规划,只做局部避障
避障机制通过邻居和障碍物信息进行局部避障,选择最优速度计算速度空间,找出不会导致碰撞的速度
路径优化使用切片式 A* 算法和拓扑优化不进行路径优化
依赖性强依赖导航网格不依赖导航网格
局部转向通过路径走廊和拐点计算基于相邻 Agent 的速度进行实时计算
实时计算每个时间步长进行路径和避障更新每个时间步长实时计算速度,确保避障
配置选项多样化配置选项配置较少,主要关注避障半径和速度
复杂性包含路径规划、优化和动态避障,多步骤复杂实现实现较简单,专注于局部避障
最大路径长度目标距离不超过 256 个多边形,需提供中间目标无全局路径规划限制
过滤器所有 Agent 使用相同的 dtQueryFilter无过滤器
最大 Agent 数量建议 20 到 30 个 Agent理论上无限制,但实际效果取决于计算性能
适用场景适合大规模人群模拟和复杂环境中的路径规划适合需要快速局部避障的场景
局限性配置和计算复杂,路径长度和 Agent 数量有限制不使用导航网格,可能导致越界,适用场景有限

Off-Mesh Connections

参考文章