转载自公众号:敢敢AUTOHUB
0. 引言:户外机器人导航的挑战
在复杂的户外环境中,机器人如何像人类一样理解"去找那栋房子"这样的自然语言指令,并自主完成长距离导航?这是机器人领域长期面临的核心挑战。传统的机器人导航系统往往依赖预先构建的地图,或者仅能处理几何信息,无法理解语义层面的目标描述。来自 NASA 喷气推进实验室(JPL)、苏黎世联邦理工学院(ETH Zürich)等机构的研究团队提出了 WildOS 系统,这是一个能够在大规模非结构化户外环境中执行开放词汇对象搜索的统一实时系统。
论文地址:https://arxiv.org/html/2602.19308v1#S5
GitHub项目主页:https://github.com/nasa-jpl/nebula2-wildos
核心创新:WildOS 将几何安全探索与语义视觉推理相结合,通过稀疏导航图维护空间记忆,同时利用基于视觉基础模型的
ExploRFM模块对图中的前沿节点进行评分。这种设计使机器人能够在探索语义上有意义的方向的同时,确保几何安全性。
在多样化的越野和城市地形中进行的大量闭环现场实验表明,WildOS 在效率和自主性方面显著优于纯几何和纯视觉基线方法。
1. WildOS 系统架构与核心技术深度解析
WildOS 采用模块化设计,将几何感知、视觉推理和规划决策有机结合。整个系统由五个主要组件构成,它们协同工作以实现长距离开放词汇对象搜索。系统的核心创新在于跨模态融合:通过稀疏导航图维护空间记忆,同时利用基于视觉基础模型的 ExploRFM 模块对图中的前沿节点进行评分,使机器人能够在探索语义上有意义的方向的同时确保几何安全性。
设计理念:通过模块解耦实现系统的可扩展性和鲁棒性,每个模块专注于特定功能,同时通过标准化接口进行数据交换。这种架构使得系统能够在不同的机器人平台和环境中快速部署和适配。
2. 稀疏导航图的增量构建与空间记忆
导航图是 WildOS 的空间记忆核心。系统将局部遍历性地图增量式地整合到稀疏导航图中,其中节点代表可达位置,边编码遍历性成本。位于已探索和未探索区域边界的节点被识别为前沿节点(Frontier Nodes),作为探索的候选点。这种基于图的表示提供了一个内存高效的结构,用于维护拓扑连接性和探索历史,使系统能够在大规模户外环境中进行可扩展的映射。相比传统的密集体素地图(Voxel Map),稀疏导航图在内存占用上降低了约90%,同时保持了相同的导航精度。
关键优势:稀疏表示不仅节省内存,还加速了路径规划算法的执行速度。在大规模户外环境(如1公里×1公里区域)中,导航图通常只需要数千个节点,而密集地图需要数百万个单元格。
数学模型与算法实现:
导航图的构建是一个增量过程,在每个时间步使用当前局部遍历性地图进行更新。图的定义为 ,其中节点 表示环境中的无碰撞位置,边 编码两个节点之间的无碰撞可遍历边。
每个节点存储两个关键属性:
自由半径:从节点到最近障碍物或未知单元的距离
探索半径:捕获节点周围环境被观察到的距离
这些半径使用障碍物和未知区域的有符号距离场(SDF, Signed Distance Field)进行更新。前沿节点集合定义为:
Ftgeo={vi∈Vt∣vi.isFrontier=true}
核心思想:通过维护自由半径和探索半径,系统能够高效判断哪些区域已被探索,哪些前沿节点仍然有效。
导航图更新的核心算法实现:
下面的 Python 代码展示了导航图的增量更新过程,包括节点半径更新、新节点采样、前沿检测和边连接四个关键步骤。
def update_navigation_graph(G_prev, T_geo_t):
"""
更新导航图
参数:
G_prev: 前一时刻的导航图
T_geo_t: 当前局部遍历性地图
返回:
G_t: 更新后的导航图
"""
# 计算有符号距离场
SDF_unk, SDF_obs = compute_sdf(T_geo_t)
# 更新现有节点的半径
for v_i in G_prev.nodes:
if v_i.within_map_bounds():
# 更新自由半径(限制在最大值)
v_i.r_f = min(SDF_obs(v_i), SDF_unk(v_i), r_f_max)
# 更新探索半径(只增不减)
v_i.r_e = max(v_i.r_e, SDF_unk(v_i))
# 移除位于障碍物内的节点
if v_i.r_f == 0:
G_prev.remove_node(v_i)
# 采样新节点
V_new = []
for _ in range(N_samples):
p_rand = sample_uniform(free_region(T_geo_t))
# 检查是否有足够的遍历性间隙
if min(SDF_obs(p_rand), SDF_unk(p_rand)) > r_trav:
# 检查是否与现有节点重叠
if all(||p_rand - p_vj|| > r_f_j for v_j in G_prev.nodes):
V_new.append(create_node(p_rand))
# 更新前沿节点
frontier_cells = detect_frontier_cells(T_geo_t)
for cell in frontier_cells:
# 跳过已探索区域内的前沿单元
if any(||cell.pos - v_j.pos|| <= v_j.r_e for v_j in G_prev.nodes):
continue
# 找到最近的无碰撞节点
v_nearest = find_nearest_collision_free_node(cell, G_prev.nodes)
if v_nearest:
v_nearest.frontier_points.append(cell.pos)
v_nearest.is_frontier = True
# 构建边连接
E_new = build_edges(G_prev.nodes + V_new, T_geo_t, r_edge)
return NavigationGraph(G_prev.nodes + V_new, G_prev.edges + E_new)
这个算法的关键在于增量式更新策略:通过维护每个节点的自由半径和探索半径,系统能够高效地判断哪些区域已被探索,哪些前沿节点仍然有效。这种稀疏表示相比密集体素地图,在大规模户外环境中具有显著的内存优势。
3. ExploRFM 视觉基础模型与语义推理
ExploRFM(Exploration and Object Reasoning Foundation Model)是 WildOS 的视觉语言核心,基于 RADIO 视觉基础模型构建。该模型融合了 DINO(几何和视觉纹理)、CLIP(视觉-语言对齐)和 SAM(边界和分割线索)三个预训练骨干网络的特征,实现了零样本对象检测和语义场景理解。
给定当前 RGB 帧 和描述目标对象的文本查询,ExploRFM 生成三个密集预测图:视觉遍历性图(估计每个像素的语义安全性)、视觉前沿评分图(定位探索候选位置)和对象相似性掩码(定位目标对象)。
这些预测在比几何感知范围更大的空间范围内提供语义理解,突破了传统激光雷达约10米的有效距离限制,将感知范围扩展到50米以上。
核心突破:ExploRFM 仅需 350 张标注图像即可训练前沿检测头,却能在从越野到城市的各种地形中泛化。这得益于 RADIO 预训练特征的强大表达能力,使系统无需针对每种环境重新训练即可部署。
模型架构与实现:
import torch
import torch.nn as nn
class ExploRFM(nn.Module):
"""
Exploration and Object Reasoning Foundation Model
基于 RADIO 的视觉语言模型,用于预测遍历性、前沿和对象相似性
"""
def __init__(self, backbone_dim=768, lang_dim=1152):
super().__init__()
# RADIO 骨干网络(预训练,冻结)
self.radio_backbone = load_radio_model('radio-v3-b')
self.radio_backbone.eval()
for param in self.radio_backbone.parameters():
param.requires_grad = False
# 语言对齐适配器(预训练)
self.lang_adapter = self.radio_backbone.get_siglip_adapter()
# 遍历性解码头
self.trav_decoder = self._build_decoder_head(backbone_dim, out_channels=1)
# 前沿解码头
self.front_decoder = self._build_decoder_head(backbone_dim, out_channels=1)
# 文本编码器(Siglip-2)
self.text_encoder = load_siglip_text_encoder()
def _build_decoder_head(self, in_dim, out_channels):
"""构建轻量级反卷积解码器"""
return nn.Sequential(
# 第一层:上采样 2x
nn.ConvTranspose2d(in_dim, 384, kernel_size=4, stride=2, padding=1),
nn.Conv2d(384, 384, kernel_size=3, padding=1),
nn.ReLU(inplace=True),
# 第二层:上采样 2x
nn.ConvTranspose2d(384, 192, kernel_size=4, stride=2, padding=1),
nn.Conv2d(192, 192, kernel_size=3, padding=1),
nn.ReLU(inplace=True),
# 第三层:上采样 2x
nn.ConvTranspose2d(192, 96, kernel_size=4, stride=2, padding=1),
nn.Conv2d(96, 96, kernel_size=3, padding=1),
nn.ReLU(inplace=True),
# 第四层:上采样 2x
nn.ConvTranspose2d(96, 48, kernel_size=4, stride=2, padding=1),
nn.Conv2d(48, 48, kernel_size=3, padding=1),
nn.ReLU(inplace=True),
# 输出层
nn.Conv2d(48, out_channels, kernel_size=1),
nn.Sigmoid()
)
def forward(self, image, text_query=None):
"""
前向传播
参数:
image: RGB 图像 [B, 3, H, W]
text_query: 文本查询(可选)
返回:
T_vis: 视觉遍历性图 [B, 1, H, W]
F_vis: 视觉前沿图 [B, 1, H, W]
S_vis: 对象相似性掩码 [B, 1, H, W](如果提供 text_query)
"""
B, _, H, W = image.shape
# 提取 RADIO 特征(补丁级)
with torch.no_grad():
F_radio = self.radio_backbone(image) # [B, H_p, W_p, D_b]
# 转换为 [B, D_b, H_p, W_p] 用于卷积
F_radio = F_radio.permute(0, 3, 1, 2)
# 预测遍历性和前沿
T_vis = self.trav_decoder(F_radio) # [B, 1, H, W]
F_vis = self.front_decoder(F_radio) # [B, 1, H, W]
# 对象相似性(如果提供文本查询)
S_vis = None
if text_query is not None:
# 获取语言对齐特征
with torch.no_grad():
F_lang = self.lang_adapter(F_radio) # [B, H_p, W_p, D_l]
# 编码文本查询
q_goal = self.text_encoder(text_query) # [B, D_l]
# 计算余弦相似度
F_lang_norm = F.normalize(F_lang, dim=-1)
q_goal_norm = F.normalize(q_goal, dim=-1)
# [B, H_p, W_p, D_l] @ [B, D_l, 1] -> [B, H_p, W_p, 1]
similarity = torch.matmul(F_lang_norm, q_goal_norm.unsqueeze(-1))
# 上采样到原始分辨率并阈值化
similarity = F.interpolate(
similarity.permute(0, 3, 1, 2),
size=(H, W),
mode='bilinear'
)
S_vis = (similarity > 0.09).float() # tau_sim = 0.09
return T_vis, F_vis, S_vis
代码关键点解析:
1. 冻结骨干网络:RADIO 特征已经足够强大,只需训练轻量级解码头(第178-181行)
2. 多任务学习:遍历性和前沿共享骨干特征,但使用独立解码器(第187、190行)
3. 语言对齐:利用预训练的 SIGLIP 适配器实现零样本对象检测(第258-276行)
4. 相似度阈值:使用 进行对象检测阈值化(第276行)
4. 超视距目标三角测量与概率定位
当目标对象出现在图像中但超出激光雷达的有效测距范围时,传统的三维定位方法失效。这是户外机器人导航面临的经典难题:激光雷达的有效测距范围通常只有10-20米,而视觉系统可以检测到数百米外的目标。
WildOS 采用基于粒子滤波的三角测量方法,通过多视角观测融合来估计目标的粗略三维位置。该方法的核心思想是在相机射线上均匀采样深度,生成三维粒子假设,然后根据每个粒子与所有观测视角主射线的对齐程度进行加权。
距离射线越近的粒子权重越高,最终通过加权平均得到目标位置估计。这种方法不需要精确的深度信息,仅依赖视觉检测和相机位姿,就能实现超视距目标定位,将导航能力从"看得见测得到"扩展到"看得见就能导航"。
突破性创新:解决了"看得见但测不到"的难题。在 NASA JPL 园区的实验中,系统成功定位了150米外的 NASA 标志,而激光雷达的有效范围仅为10米。三角测量的位置估计误差约为目标距离的5-10%,足以支持粗略的路径规划。
粒子滤波三角测量算法:
下面的代码展示了基于粒子滤波的三角测量过程。算法分为三个步骤:(1)为每个视角生成粒子假设,(2)根据粒子到射线的距离计算权重,(3)加权平均得到最终位置估计。关键参数 ,深度范围 米。
import numpy as np
def triangulate_goal(detections, camera_poses, K, N_particles=1000, d_min=1.0, d_max=100.0):
"""
基于多视角检测的目标三角测量
参数:
detections: 检测列表,每个包含 (mask, T_cam)
camera_poses: 相机位姿列表 [R|t]
K: 相机内参矩阵
N_particles: 每个视角采样的粒子数
d_min, d_max: 深度采样范围
返回:
p_goal: 估计的目标三维位置
"""
particles = []
# 步骤1:为每个检测生成粒子
for mask, T_cam in detections:
# 从掩码中随机采样像素
mask_pixels = np.argwhere(mask > 0)
sampled_pixels = mask_pixels[
np.random.choice(len(mask_pixels), N_particles, replace=True)
]
for u, v in sampled_pixels:
# 随机采样深度
d = np.random.uniform(d_min, d_max)
# 反投影到相机坐标系
p_cam = d * np.linalg.inv(K) @ np.array([u, v, 1])
# 转换到世界坐标系
R, t = T_cam[:3, :3], T_cam[:3, 3]
p_world = R @ p_cam + t
particles.append(p_world)
particles = np.array(particles) # [N_total, 3]
# 步骤2:计算每个粒子的权重
weights = np.zeros(len(particles))
for mask, T_cam in detections:
# 计算掩码质心在图像中的位置
mask_pixels = np.argwhere(mask > 0)
centroid_uv = mask_pixels.mean(axis=0)
# 计算主射线方向(从相机中心到质心)
ray_dir = np.linalg.inv(K) @ np.array([centroid_uv[1], centroid_uv[0], 1])
ray_dir = ray_dir / np.linalg.norm(ray_dir)
# 转换到世界坐标系
R, t = T_cam[:3, :3], T_cam[:3, 3]
ray_dir_world = R @ ray_dir
ray_origin = t
# 计算每个粒子到射线的距离
for i, p in enumerate(particles):
# 点到射线的最短距离
v = p - ray_origin
proj_length = np.dot(v, ray_dir_world)
closest_point = ray_origin + proj_length * ray_dir_world
dist = np.linalg.norm(p - closest_point)
# 距离越近,权重越高(使用倒数)
weights[i] += 1.0 / (dist + 1e-6)
# 步骤3:加权平均得到最终估计
weights = weights / weights.sum()
p_goal = (particles.T @ weights).T
return p_goal
算法关键点解析:
1. 粒子生成(第319-338行):在每个视角的相机射线上均匀采样深度 ,生成 个三维粒子假设
2. 权重计算(第342-368行):计算每个粒子到所有观测射线的距离,使用倒数作为权重
3. 加权平均(第370-372行):归一化权重后进行加权平均,得到最终位置估计
方法优势:
• 鲁棒性:通过多视角融合减少单次检测的误差
• 概率性:权重机制自然地抑制了虚假检测
• 实时性:
粒子采样和加权计算都是轻量级操作,适合在线运行
5. 视觉-几何融合评分与跨模态决策
WildOS 的核心创新在于将几何前沿节点与视觉语义线索融合,实现跨模态决策。传统的纯几何方法只能看到激光雷达范围内的障碍物,容易做出短视的决策(如直接朝目标前进直到遇到障碍物);而纯视觉方法虽然能看得更远,但缺乏空间记忆,容易陷入振荡和重复探索。WildOS 通过将几何前沿节点投影到图像平面,并基于三个置信度分量计算综合评分,成功融合了两种模态的互补优势。评分函数包含:目标置信度(衡量前沿方向与目标方向的对齐度)、可达性置信度(基于图像空间中的最小成本路径)和前沿置信度(视觉前沿预测的置信度)。最终评分为三者的乘积 ,这种乘法形式确保了只有同时满足目标导向、可达性和前沿置信度的节点才能获得高分。
设计哲学深度解析:
• 目标导向:优先选择朝向目标的前沿,避免盲目探索
• 可达性优先:抑制视觉上可见但几何上不可达的前沿(如围栏后的开阔区域)
• 视觉引导
:利用视觉前沿预测识别有希望的探索方向(如障碍物之间的间隙)
在圆形围栏实验中,WildOS 正确识别了围栏间的开口,而纯几何方法直接朝目标前进直到撞上围栏,纯视觉方法则在围栏前振荡。这证明了跨模态融合的有效性。
评分计算算法与实现:
下面的代码展示了前沿节点评分的完整计算过程。算法遍历图像中所有可遍历的视觉前沿像素,计算三个置信度分量,并选择最高评分。关键阈值:(遍历性),(前沿置信度)。
def compute_frontier_score(frontier_node, image, T_vis, F_vis, goal_pos, robot_pos, K):
"""
计算几何前沿节点的视觉语义评分
参数:
frontier_node: 几何前沿节点
image: RGB 图像
T_vis: 视觉遍历性图 [H, W]
F_vis: 视觉前沿图 [H, W]
goal_pos: 目标位置
robot_pos: 机器人位置
K: 相机内参
返回:
score: 前沿节点评分 [0, 1]
"""
# 将前沿节点投影到图像平面
uv = project_to_image(frontier_node.pos, K)
if not is_valid_projection(uv, image.shape):
return 0.3 # 默认评分
u, v = int(uv[0]), int(uv[1])
H, W = image.shape[:2]
# 计算目标方向
h_goal = (goal_pos - frontier_node.pos)
h_goal = h_goal / np.linalg.norm(h_goal)
# 在图像中搜索最佳视觉前沿
best_score = 0.0
for p_v in range(H):
for p_u in range(W):
# 只考虑可遍历的像素
if T_vis[p_v, p_u] < 0.9: # tau_trav
continue
# 只考虑高置信度的视觉前沿
if F_vis[p_v, p_u] < 0.6: # tau_front
continue
# 1. 计算目标置信度
ray_dir = np.linalg.inv(K) @ np.array([p_u, p_v, 1])
ray_dir = ray_dir / np.linalg.norm(ray_dir)
# 余弦相似度映射到 [0.5, 1]
cos_sim = np.dot(ray_dir[:2], h_goal[:2])
G_conf = (3 + cos_sim) / 4
# 2. 计算可达性置信度(基于图像空间最短路径)
mcip_dist = compute_min_cost_image_path(
(u, v), (p_u, p_v), T_vis, tau_trav=0.9
)
R_conf = 1 - np.tanh(mcip_dist / (H + W))
# 3. 前沿置信度
F_conf = F_vis[p_v, p_u]
# 综合评分
score = G_conf * R_conf * F_conf
best_score = max(best_score, score)
return best_score
def compute_min_cost_image_path(start, end, T_vis, tau_trav):
"""
计算图像空间中的最小成本路径(Dijkstra)
参数:
start: 起始像素 (u, v)
end: 目标像素 (u, v)
T_vis: 遍历性图
tau_trav: 遍历性阈值
返回:
路径成本
"""
from heapq import heappush, heappop
H, W = T_vis.shape
visited = set()
pq = [(0, start)] # (cost, pixel)
while pq:
cost, (u, v) = heappop(pq)
if (u, v) == end:
return cost
if (u, v) in visited:
continue
visited.add((u, v))
# 8-连通邻域
for du, dv in [(-1,0), (1,0), (0,-1), (0,1), (-1,-1), (-1,1), (1,-1), (1,1)]:
nu, nv = u + du, v + dv
if 0 <= nu < W and 0 <= nv < H and (nu, nv) not in visited:
if T_vis[nv, nu] > tau_trav:
# 边权重:遍历性越低,成本越高
edge_cost = 1.0 / (T_vis[nv, nu] + 1e-6)
heappush(pq, (cost + edge_cost, (nu, nv)))
return float('inf') # 无法到达
算法关键点解析:
1. 投影检查(第423-427行):将前沿节点投影到图像平面,无效投影返回默认评分 0.3
2. 目标置信度计算(第449-455行):使用余弦相似度 映射到 ,公式为
3. 可达性置信度计算(第457-461行):基于 Dijkstra 最短路径,使用 归一化:
4. 综合评分(第467-468行):选择所有可遍历前沿像素中的最高评分
计算复杂度:对于 图像,最坏情况下需要遍历所有像素并计算最短路径,复杂度为 。实际运行中通过早期终止和阈值过滤大幅降低计算量。
6. 分层规划器与多层次决策架构
分层规划器是 WildOS 实现短程安全性与长程语义推理统一的关键。系统采用两层规划架构:高层规划器使用评分导航图规划到粗略目标估计的全局路径,低层规划器计算安全的、动态可行的局部路径并输出控制命令。
这种分层设计源于一个核心洞察:全局规划需要语义理解(知道往哪个方向探索),局部规划需要几何精度(避开障碍物)。如果尚未观察到目标对象,高层规划器会回退到任务开始时提供的近似先验目标(如用户指定的GPS坐标或方向)。路径上的中间短程目标(通常距离当前位置5-10米)被传递给局部规划器,后者使用局部代价地图计算安全的、动态可行的路径。这种设计使得系统能够在保证短程几何安全的同时,利用视觉信息进行长程语义推理,避免了纯几何方法的短视性和纯视觉方法的不安全性。
分层设计的深度优势:
• 解耦复杂性:全局规划在稀疏图上进行(数千节点),局部规划在密集地图上进行(数百万单元格),各自使用最适合的数据结构
• 频率分离:全局规划以1 Hz运行(语义变化慢),局部规划以10 Hz运行(需要快速响应动态障碍物)
• 失败恢复
:局部规划失败时(如遇到未预见的障碍物),全局规划器可以重新规划,而不需要重启整个系统
在死胡同实验中,当机器人遇到被汽车阻挡的路径时,局部规划器检测到无法前进,触发全局重新规划。高层规划器利用导航图记忆该路径已被探索且不可达,转而选择另一条路径。这种分层恢复机制是系统鲁棒性的关键。
7. 总结:迈向通用户外机器人自主性
WildOS 代表了户外机器人导航领域的重要进展,它成功地将视觉基础模型的语义理解能力与传统几何方法的安全性和可靠性相结合。通过稀疏导航图维护空间记忆,通过 ExploRFM 提供长距离视觉推理,WildOS 实现了真正的语义感知、记忆驱动的大规模探索。
WildOS 的成功展示了视觉基础模型在机器人领域的巨大潜力。仅用 350 张标注图像训练的模型就能在从越野到城市的各种地形中泛化,这突显了预训练特征的表达能力。更重要的是,WildOS 证明了"记忆"对于长时程自主性的关键作用——纯视觉方法虽然能提供丰富的语义线索,但缺乏空间记忆会导致重复探索和振荡行为。
217