摘要
前两篇已经把边界讲清了:Foxglove 不是权限系统,foxglove_bridge 也不是按用户实时判权的权限中心。
这一篇就不再绕回概念了。
目标很直接:把一套默认能连、默认好用的 Foxglove + ROS 2 系统,收成上线前更像样的结构。
要动的地方主要有四个:
foxglove_bridge从默认全开改成按角色收口- WebSocket 入口只走网关,不让 bridge 裸露
- ROS 2 节点按观测、代理、执行拆开
- 高风险动作只走
/ui/*代理,不直通/cmd_vel、底层 Service 和参数
下面配置按核对到的官方 foxglove_bridge ROS 2 Humble 文档来写。这里有个前提容易被忽略:这些参数必须在启动时设置,运行中不能动态改。也就是说,一个 bridge 不适合拿来做“用户来了再切权限”的入口。
一、先对齐 bridge 默认暴露面
先看默认值。很多坑不是配置写错,而是默认值太适合调试,不适合直接带进生产。
| 参数 | 官方默认 | 上线建议 |
|---|---|---|
address |
0.0.0.0 |
改成 127.0.0.1,外部接入交给网关 |
tls |
false |
bridge 本机回环可关;跨主机直连必须上 TLS/WSS |
topic_whitelist |
[".*"] |
只放观测 Topic |
service_whitelist |
[".*"] |
只放 /ui/* 高层代理 Service |
param_whitelist |
[".*"] |
默认封死,确需维护再单独代理 |
client_topic_whitelist |
[".*"] |
默认封死,不让前端直接 publish |
capabilities |
clientPublish、parameters、parametersSubscribe、services、connectionGraph、assets |
按角色只开需要的能力 |
asset_uri_allowlist |
默认允许部分 package:// 资源格式 |
不需要资源访问就封死 |
这里注意两个细节。
第一,官方参数名仍然叫 *_whitelist,文章里沿用原名,不额外改成 allowlist。
第二,(?!) 是官方也在用的“永不匹配”正则写法。需要把某类入口封死时,用它比留空更清楚。
二、按角色拆 bridge 实例
不要指望一个 bridge 同时服务 Viewer、Operator、Maintenance 三类人。
我更建议拆三套端口,前面由网关按登录态和角色转发。配置多一点,但排查时清楚很多。
Viewer:只读观测入口
这一套只看,不动。
ros2 launch foxglove_bridge foxglove_bridge_launch.xml \
address:=127.0.0.1 \
port:=8765 \
capabilities:='[connectionGraph]' \
topic_whitelist:='["^/tf$","^/tf_static$","^/map$","^/odom$","^/scan$","^/camera/.*$","^/diagnostics$","^/robot/status$","^/battery_state$"]' \
service_whitelist:='["(?!)"]' \
param_whitelist:='["(?!)"]' \
client_topic_whitelist:='["(?!)"]' \
asset_uri_allowlist:='["(?!)"]'
这套配置里,capabilities 只留 connectionGraph。services、parameters、clientPublish 都别开。
如果 Viewer 还能调 Service、改参数或者 publish,说明这一层还没收住。
Operator:只允许高层动作
Operator 可以操作,但只能碰高层代理。
ros2 launch foxglove_bridge foxglove_bridge_launch.xml \
address:=127.0.0.1 \
port:=8766 \
capabilities:='[services,connectionGraph]' \
topic_whitelist:='["^/tf$","^/tf_static$","^/map$","^/odom$","^/scan$","^/camera/.*$","^/diagnostics$","^/robot/status$","^/task/summary$","^/localization/status$"]' \
service_whitelist:='["^/ui/start_task$","^/ui/pause_task$","^/ui/resume_task$","^/ui/cancel_task$","^/ui/manual_jog$","^/ui/set_initial_pose$","^/ui/clear_fault$"]' \
param_whitelist:='["(?!)"]' \
client_topic_whitelist:='["(?!)"]' \
asset_uri_allowlist:='["(?!)"]'
这套配置最该盯的不是加了 /ui/manual_jog,而是没有把下面这些东西放进去:
/cmd_vel/goal_pose/controller/*/driver/*- 任何底层恢复 Service
- 任何控制器参数
Operator 可以发起动作,但动作先到代理节点,不能落到底层控制口。
Maintenance:维护窗口内短时放开
维护入口不要常驻全开。现场为了省事把维护口一直挂着,后面基本都会后悔。
ros2 launch foxglove_bridge foxglove_bridge_launch.xml \
address:=127.0.0.1 \
port:=8767 \
capabilities:='[services,parameters,parametersSubscribe,connectionGraph]' \
topic_whitelist:='["^/diagnostics$","^/robot/status$","^/maintenance/.*$"]' \
service_whitelist:='["^/ui/run_diagnostic$","^/ui/recover_device$","^/ui/apply_maintenance_profile$"]' \
param_whitelist:='["^/maintenance_proxy/.*$"]' \
client_topic_whitelist:='["(?!)"]' \
asset_uri_allowlist:='["(?!)"]'
这套只适合维护窗口。
生产里至少加三条限制:
- 网关只给维护账号转发到
8767 - 维护窗口结束后停掉这一实例
- 所有动作都落审计
三、用网关统一接入和分流
bridge 绑到 127.0.0.1 后,对外只暴露网关。
下面这个 Nginx 片段只演示分流,不是一套完整认证方案。重点是不同角色落到不同 bridge 端口。
map $http_x_user_role $foxglove_upstream {
default "";
viewer 127.0.0.1:8765;
operator 127.0.0.1:8766;
maintenance 127.0.0.1:8767;
}
server {
listen 443 ssl;
server_name robot.example.com;
ssl_certificate /etc/ssl/certs/robot.example.com.crt;
ssl_certificate_key /etc/ssl/private/robot.example.com.key;
location /foxglove/ {
if ($foxglove_upstream = "") {
return 403;
}
proxy_pass http://$foxglove_upstream;
proxy_http_version 1.1;
proxy_set_header Upgrade $http_upgrade;
proxy_set_header Connection "upgrade";
proxy_set_header Host $host;
proxy_read_timeout 3600s;
}
}
现场不要真的相信 X-User-Role 这种浏览器可伪造头。它应该来自前置认证模块、内网认证网关,或者后端鉴权后的结果。
网关层只管这几件事:
- 谁能连
- 连到哪套 bridge
- 连接和操作怎么审计
不要把“当前能不能点动”“现在能不能恢复故障”这类业务状态判断塞到网关里。那些判断放代理节点更合适。
四、按观测、代理、执行拆节点
bridge 收口以后,ROS 2 节点也要跟着拆。否则入口看起来收紧了,里面还是一锅粥。
这张图要表达的其实就一句话:bridge 不能摸核心执行层。
一个够用的最小拆法如下。
| 层 | 节点 | 对外接口 | 对内接口 |
|---|---|---|---|
| 观测层 | StateAggregator、DiagnosticAggregator |
/robot/status、/task/summary、/diagnostics |
订阅底层状态 |
| 代理层 | UiActionProxy |
/ui/start_task、/ui/manual_jog |
调任务、导航、设备代理 |
| 代理层 | NavigationProxy |
内部 Service | 调导航栈 |
| 代理层 | DeviceActionProxy |
内部 Service | 调设备控制器 |
| 执行层 | 导航、底盘、驱动、互锁 | 不给 bridge | 只接受代理层调用 |
如果 foxglove_bridge_operator 还能看到 /cmd_vel 或底层驱动 Service,那这套分层只是画在图上,还没有落到系统里。
五、用 SROS2 补节点级硬边界
bridge 白名单只是入口收口,不是 ROS 2 硬权限。
想做到“上层 bridge 配错了,也不能打到底层”,还得补 SROS2 / DDS Security。
最低要求先把这三项打开:
export ROS_SECURITY_ENABLE=true
export ROS_SECURITY_STRATEGY=Enforce
export ROS_SECURITY_KEYSTORE=/tmp/robot-security-keystore
ROS_SECURITY_ENABLE=true 是总开关。
ROS_SECURITY_STRATEGY=Enforce 的意思是:安全制品不完整、权限不满足,节点就别继续以不安全状态启动。
权限文件里别只给一个大而全的 enclave。至少拆到下面这个粒度:
/foxglove/viewer_bridge
/foxglove/operator_bridge
/foxglove/maintenance_bridge
/proxy/ui_action
/proxy/navigation
/proxy/device
/core/navigation
/core/base_controller
/core/device_controller
下面这个片段只演示思路:operator_bridge 可以订阅观测 Topic,可以调用 /ui/* 对应的 ROS Service,但不能发布 /cmd_vel。
ROS 2 安全文档里有个细节很容易写错:权限 XML 里写的是 DDS 名称,不是 ROS 名称。普通 Topic 通常会映射成 rt/<topic>,Service 还会拆成请求和响应对应的 DDS Topic。实际项目不要手拍脑袋写全量文件,先用 sros2 模板生成,再逐项审。
<grant name="/foxglove/operator_bridge">
<subject_name>CN=/foxglove/operator_bridge</subject_name>
<validity>
<not_before>2026-01-01T00:00:00</not_before>
<not_after>2036-01-01T00:00:00</not_after>
</validity>
<allow_rule>
<domains>
<id>0</id>
</domains>
<subscribe>
<topics>
<topic>rt/tf</topic>
<topic>rt/tf_static</topic>
<topic>rt/map</topic>
<topic>rt/odom</topic>
<topic>rt/scan</topic>
<topic>rt/diagnostics</topic>
<topic>rt/robot/status</topic>
<topic>rt/task/summary</topic>
<topic>rt/localization/status</topic>
<topic>rt/parameter_events</topic>
</topics>
</subscribe>
</allow_rule>
<allow_rule>
<domains>
<id>0</id>
</domains>
<publish>
<topics>
<topic>rq/ui/manual_jogRequest</topic>
</topics>
</publish>
<subscribe>
<topics>
<topic>rr/ui/manual_jogReply</topic>
</topics>
</subscribe>
</allow_rule>
<default>DENY</default>
</grant>
这段不要复制进生产。
生产里要按实际 ROS 发行版、RMW、Service 类型和命名空间生成并验证。这里要落下来的原则只有一个:operator_bridge 没有 /cmd_vel 的 publish 权限。哪怕上层误开了 clientPublish,底层也不放行。
六、动作代理要做校验和收口
动作代理最怕写成“换个名字继续透传”。
以手动点动为例,前端不要给线速度、角速度、持续时间。让前端只给离散动作就够了:
# 文件:srv/ManualJog.srv
string robot_id
string direction
string speed_level
uint32 duration_ms
---
bool accepted
string reason
代理层再把它映射成受控输出。
import rclpy
from geometry_msgs.msg import Twist
from rclpy.node import Node
from robot_interfaces.srv import ManualJog
class UiActionProxy(Node):
def __init__(self):
super().__init__("ui_action_proxy")
self.mCmdVelPublisher = self.create_publisher(Twist, "/cmd_vel", 10)
self.mManualJogService = self.create_service(
ManualJog,
"/ui/manual_jog",
self.handleManualJog,
)
self.mSpeedTable = {
"low": 0.05,
"normal": 0.12,
}
self.mMaxDurationMs = 500
self.mStopTimer = None
def handleManualJog(self, request, response):
checkResult = self.checkManualJog(request)
if checkResult:
response.accepted = False
response.reason = checkResult
self.writeAudit(request, "reject", checkResult)
return response
twist = self.buildTwist(request.direction, request.speed_level)
self.mCmdVelPublisher.publish(twist)
self.scheduleStop(request.duration_ms)
response.accepted = True
response.reason = "accepted"
self.writeAudit(request, "accepted", "")
return response
def checkManualJog(self, request):
if not self.isRobotAssigned(request.robot_id):
return "机器人不属于当前会话"
if not self.isManualMode(request.robot_id):
return "当前不是手动模式"
if self.hasActiveTask(request.robot_id):
return "自动任务未退出"
if self.hasSafetyLock(request.robot_id):
return "存在安全互锁"
if request.duration_ms == 0:
return "点动时间必须大于 0"
if request.duration_ms > self.mMaxDurationMs:
return "点动时间超过上限"
if request.direction not in {"forward", "backward", "left", "right"}:
return "方向不在允许范围"
if request.speed_level not in self.mSpeedTable:
return "速度档位不在允许范围"
return ""
def buildTwist(self, direction, speedLevel):
speed = self.mSpeedTable[speedLevel]
twist = Twist()
if direction == "forward":
twist.linear.x = speed
elif direction == "backward":
twist.linear.x = -speed
elif direction == "left":
twist.angular.z = speed
elif direction == "right":
twist.angular.z = -speed
return twist
def scheduleStop(self, durationMs):
if self.mStopTimer is not None:
self.mStopTimer.cancel()
self.destroy_timer(self.mStopTimer)
self.mStopTimer = self.create_timer(durationMs / 1000.0, self.stopJog)
def stopJog(self):
self.mCmdVelPublisher.publish(Twist())
if self.mStopTimer is not None:
self.mStopTimer.cancel()
self.destroy_timer(self.mStopTimer)
self.mStopTimer = None
def isRobotAssigned(self, robotId):
return bool(robotId)
def isManualMode(self, robotId):
return True
def hasActiveTask(self, robotId):
return False
def hasSafetyLock(self, robotId):
return False
def writeAudit(self, request, result, reason):
self.get_logger().info(
f"action=manual_jog robot_id={request.robot_id} "
f"direction={request.direction} speed_level={request.speed_level} "
f"duration_ms={request.duration_ms} result={result} reason={reason}"
)
def main():
rclpy.init()
node = UiActionProxy()
rclpy.spin(node)
rclpy.shutdown()
这段代码里有用的不是 Python 写法,而是判断顺序:
- 先看机器人是否属于当前会话
- 再看当前是否手动模式
- 再看自动任务是否退出
- 再看急停、碰撞、区域互锁
- 最后才把离散档位转成
/cmd_vel
如果代理只是把请求里的 linear_x、angular_z 原样发到 /cmd_vel,那不叫代理,只是换了入口。
七、参数修改也走业务代理
参数不要交给 Foxglove 面板。这个口子看着方便,现场最容易被滥用。
按三类处理就够。
| 类型 | 例子 | 做法 |
|---|---|---|
| 永远不进 UI | 安全阈值、PID、驱动参数、调试开关 | 不进 param_whitelist |
| 只读展示 | 当前地图、任务速度上限、定位状态 | 聚合成状态 Topic |
| 必须修改 | 速度配置、维护配置、重定位申请 | 做成 /ui/* Service |
比如速度档位,不要改控制器参数。
暴露成下面这种业务接口会更好管:
# 文件:srv/UpdateSpeedProfile.srv
string robot_id
string profile_name
---
bool accepted
string reason
代理节点内部再校验:
- 当前角色能不能改
- 当前任务状态能不能改
profile_name是否在白名单- 是否要二次确认
- 是否要写审计
这样一来,参数变化也是业务动作,不是临时调参。
八、验收要分 ROS 图和 bridge 暴露面
改完以后别只看页面能不能打开,要分两层验。
ros2 命令看到的是 ROS 图,不是 bridge 暴露面。它只能确认接口在系统里是否存在,不能证明 Viewer 或 Operator 能不能通过 Foxglove 访问这些接口。
ROS 侧:确认接口存在
ros2 service list | grep '^/ui/'
ros2 topic list | grep '^/cmd_vel$'
ros2 param list | grep -E 'controller|driver|safety' || true
这里的预期是:/ui/* 代理存在,/cmd_vel 底层 Topic 也可能存在,但它们不能被同一套 bridge 全量暴露出去。
Foxglove 侧:确认暴露面
分别连接三套入口验:
| 入口 | 应该看到 | 不应该看到 |
|---|---|---|
| Viewer | 地图、状态、诊断、连接图 | /ui/* Service、参数面板、client publish |
| Operator | 观测 Topic、/ui/* Service |
/cmd_vel 发布入口、底层驱动 Service、参数写入口 |
| Maintenance | 维护 Topic、有限维护 Service、维护代理参数 | 长期开启的全量参数写、原始控制透传 |
这一层要在 Foxglove 里验,不要拿 ros2 service list 代替。
反向测试:验证底层权限拒绝
这条测试有个前置条件:/foxglove/operator_bridge 这个 enclave 必须已经有完整安全制品。
测试时先把 keystore 放到当前用户可写目录,别一上来就往 /opt 写:
ros2 security create_keystore /tmp/robot-security-keystore
ros2 security create_enclave /tmp/robot-security-keystore /foxglove/operator_bridge
确认目录里有证书、密钥和权限文件:
ls /tmp/robot-security-keystore/enclaves/foxglove/operator_bridge
至少应该能看到 cert.pem、key.pem、permissions.p7s 这类文件。不同 RMW 和生成方式下文件名可能有细节差异,但只建一个空目录肯定不够。
如果这里报目录不存在,说明 enclave 没生成。如果报 couldn't find all security files! 或 rcl node's rmw handle is invalid,通常是手工 mkdir -p 了空目录,重新跑上面的 ros2 security create_enclave。
确认制品存在后,再跑反向测试:
ROS_SECURITY_ENABLE=true \
ROS_SECURITY_STRATEGY=Enforce \
ROS_SECURITY_KEYSTORE=/tmp/robot-security-keystore \
ROS_SECURITY_ENCLAVE_OVERRIDE=/foxglove/operator_bridge \
ros2 topic pub /cmd_vel geometry_msgs/msg/Twist "{linear: {x: 0.1}, angular: {z: 0.0}}" \
--once \
--wait-matching-subscriptions 0
这条命令不是让你在生产环境随手跑。它应该放在隔离测试环境里,用 ROS_SECURITY_ENCLAVE_OVERRIDE 切到 operator_bridge 同一个 enclave,验证它没有 /cmd_vel 的 publish 权限。--wait-matching-subscriptions 0 是为了避免测试环境里没有订阅者时命令一直等。
SROS2:确认强制模式
echo $ROS_SECURITY_ENABLE
echo $ROS_SECURITY_STRATEGY
echo $ROS_SECURITY_KEYSTORE
期望是:
true
Enforce
/tmp/robot-security-keystore
正确结果不是“发出去了但没人理”,而是安全策略直接拒绝。
九、按风险顺序改造
现有系统已经在跑时,别一次全重构。
按这个顺序来:
- 先把 Topic、Service、Parameter 暴露清单列出来
- 先拆 Viewer 和 Operator 两套 bridge
- 把
/cmd_vel、故障恢复、设备原始控制迁到/ui/*代理 - 参数面板默认封死,确需修改的参数改成业务 Service
- 最后补
SROS2 / DDS Security,把节点级硬边界落下来
这个顺序的好处是每一步都能单独验收。
先别急着画一张很完整的权限架构图。先把最危险的直通口收掉。
小结
Foxglove 权限落地,别只盯“按钮给不给显示”。更该看下面这些事有没有真的做到:
- bridge 默认不全开
- Viewer 和 Operator 不共用同一个暴露面
- 前端不直连底层控制接口
- 高风险动作都经过代理节点
- 参数修改被当成业务动作处理
- SROS2 给节点级访问兜底
做到这里,Foxglove 仍然是 Foxglove,负责可视化和入口桥接。
权限要落在网关、bridge 收口、ROS 2 安全制品和业务代理这几层。每层少做一点,但边界要清楚。
评论区