本文档属于 Robotics Tutorial 项目,作者:Pengfei Guo,达妙科技。采用 CC BY 4.0 协议,转载请注明出处。
D05 遥操作导论——二端口网络模型、透明度与四通道架构¶
本章定位:本章是遥操作理论与数据采集(D05-D08)的起点,从双臂协同(D01-D04 中两条机器臂之间的协调)转向**人臂与机器臂之间的协调**。遥操作的核心矛盾是"透明度 vs 稳定性"——操作者想感受到远端环境的真实力(透明),但通信延迟会破坏闭环稳定性。二端口网络模型是分析这一矛盾的统一数学框架,本章建立理论基础,D06 讲散射/波变量的完整推导解决延迟下的稳定性,D07 讲 TDPA 工程实现。
适用范围:二端口网络和透明度概念对触觉设备、VR 力反馈、外骨骼、康复机器人均适用。
前置依赖:F01(阻抗/导纳概念)、F02.4(无源性——储能函数/供给率)、基础控制理论(传递函数/Nyquist/BIBO 稳定性)
下游章节:D06(波变量/无源通信理论)、D07(TDPA 工程实现)、D08(运动映射与遥操作数据采集)
建议用时:2 周(15-20 小时)
前置自测 ⭐¶
📋 答不出 >= 2 题 → 先回前置章节复习
| 编号 | 问题 | 答不出时回顾 |
|---|---|---|
| 1 | 阻抗/导纳定义:写出机械阻抗 \(Z(s) = F(s)/V(s)\) 和导纳 \(Y(s) = V(s)/F(s)\) 的定义。弹簧-阻尼-质量系统的阻抗是什么? | F01 阻抗导纳二分法 |
| 2 | 无源性定义:一个单端口系统是被动的(passive),当且仅当什么条件成立?写出端口无源性的能量不等式。 | F02.4 无源性基础 |
| 3 | 传递函数稳定性:什么是 BIBO 稳定?传递函数的极点必须满足什么条件?Nyquist 判据判断什么? | 控制理论基础 |
| 4 | 二端口网络:电气中的二端口网络有哪些参数化方式(Z/Y/H/T 参数)?它们之间如何互换? | 电路理论基础 |
| 5 | D04 中 ALOHA 的控制模式:ALOHA 使用什么底层控制?为什么它没有力反馈?这与本章将讨论的"透明度"有什么关系? | D04 双臂学习 |
本章目标¶
学完本章后,你应该能够:
- **建立**遥操作系统的二端口网络模型——定义端口变量(力/速度)、混合参数 h、操作者感受阻抗 \(Z_{to}\)
- **推导**理想透明度的严格条件 \(H_{ideal} = \begin{bmatrix} 0 & 1 \\ -1 & 0 \end{bmatrix}\),并理解其物理含义
- 掌握 Llewellyn 绝对稳定性准则的四个条件,能计算给定架构的稳定因子 \(\eta(\omega)\)
- **理解**透明度-稳定性 trade-off 的数学本质——\(\eta = 0\) 意味着零鲁棒裕度
- **区分**四种子架构(PP/PF/FP/FF)的 h 矩阵、透明度极限和工程适用场景
- 掌握 Z-width 概念和虚拟墙被动条件 \(b > KT/2\),理解采样率对力反馈质量的决定性影响
- **定量分析**时延如何破坏透明度,并理解为什么 >200 ms 时 Llewellyn 准则无解
1. 遥操作的历史起源与核心矛盾 ⭐¶
1.1 从核处理到深空——遥操作的七十年¶
遥操作(teleoperation)起源于人类需要在危险或不可达环境中执行物理操作的需求。理解其历史演进有助于理解当前理论框架的"为什么"。
第一代:机械联动(1940s-1950s)
Raymond Goertz 在美国阿贡国家实验室(ANL)设计了第一台主从遥操作器,用于处理放射性材料。这是纯机械系统——主端和从端通过钢丝绳和滑轮直接机械连接:
Goertz 1952 机械主从臂
══════════════════════════════════
操作者(隔离墙外) 放射区(隔离墙内)
┌─────────┐ ┌─────────┐
│ Master │═══钢丝绳═══════│ Slave │
│ (操作端) │ │ (执行端) │
└─────────┘ └─────────┘
↑ ↓
人手施力 f_h 环境接触力 f_e
人手速度 v_m 从端速度 v_s
完美透明: f_h = f_e, v_m = v_s(理想刚性连接)
完美稳定: 纯被动机械系统(无能量源)
代价: 距离受限(~3m)、无放大/缩小
本质洞察:Goertz 的机械主从臂实现了**完美透明度**和**绝对稳定性**的同时满足——这是后来所有电控方案都无法达到的。为什么?因为机械联动是纯被动系统(没有电机、没有控制器、没有通信),不存在能量创生的可能。所有后续的理论努力(二端口网络、波变量、TDPA)本质上都是在**用主动控制系统模拟被动机械系统的行为**。
第二代:电控双边(1960s-1980s)
机械联动的距离限制催生了电控方案——用电机替代钢丝绳,用传感器和通信线替代机械连接。但立刻产生了新问题:
| 问题 | 来源 | 后果 |
|---|---|---|
| 不稳定 | 控制器延迟+采样离散化 | 硬墙接触时振荡 |
| 透明度下降 | 电机惯量+齿轮摩擦+通信延迟 | 操作者感受不到真实环境 |
| 延迟效应 | 电信号传播+计算延迟 | 操作者动作和反馈不同步 |
Ferrell (1965) 在 MIT 的实验首次定量揭示了**时延对遥操作的摧毁性影响**:
Ferrell 1965 时延实验结果
══════════════════════════════════
延迟 T 任务完成时间倍数 主观评价
0 ms 1.0x "自然"
50 ms 1.2x "可接受"
200 ms 2.0x "困难"
500 ms 3.5x "几乎不可能"
1000 ms 5.0x+ "完全无法操作"
结论: 延迟 > 200 ms 时,人类操作策略
从"连续控制"切换为"移动-等待-观察"(move-and-wait)
这一实验结果直接驱动了 1980s-1990s 的理论发展——如何在有延迟的电控系统中同时保持稳定性和透明度。
第三代:理论化与体系化(1989-2006)
| 年份 | 里程碑 | 核心贡献 |
|---|---|---|
| 1989 | Anderson-Spong | 散射变换→任意常数时延下的无源性 |
| 1989 | Hannaford | 混合二端口网络模型→四种子架构 |
| 1991 | Niemeyer-Slotine | 波变量→传输线物理直觉 |
| 1993 | Lawrence | 透明度严格定义→Llewellyn 准则引入 |
| 1994 | Yokokohji-Yoshikawa | 理想运动觉耦合三条件 |
| 1994 | Colgate-Brown | Z-width→虚拟墙被动条件 |
| 2001 | Hashtrudi-Zaad-Salcudean | 阻抗/导纳 master x slave 选型原则 |
| 2006 | Hokayem-Spong 综述 | 领域历史地图 |
1.2 遥操作系统的三种控制范式¶
根据人类与机器人之间的控制权分配,遥操作可分为三种范式:
| 范式 | 人的角色 | 机器人自主度 | 典型应用 |
|---|---|---|---|
| Direct(直接遥操作) | 连续控制所有 DOF | 零(纯执行) | 核处理、爆炸物处理 |
| Shared(共享控制) | 提供高级意图 | 部分(如自动避障) | 手术机器人(da Vinci) |
| Supervisory(监督控制) | 下达目标/监控 | 高(自主规划执行) | 深空探测(火星车) |
本章聚焦 Direct 范式——操作者连续控制机器人的每个 DOF,机器人提供力反馈。这是理论分析最深入、对透明度要求最高的范式。
跨领域类比:遥操作的三种范式类似于自动驾驶的分级:Direct 对应 L0(人完全控制),Shared 对应 L2-L3(人机共驾),Supervisory 对应 L4-L5(机器自主)。就像自动驾驶中 L3 的"人机切换"是最危险的状态,遥操作中 Shared Control 的"人机意图冲突"也是最难处理的问题。
1.3 核心矛盾——透明度 vs 稳定性¶
遥操作系统设计的核心矛盾用一句话概括:
操作者想完美感受远端环境(透明度),但通信延迟会破坏系统稳定性。
这一矛盾不是可以通过更好的算法"解决"的——它是由物理定律决定的基本限制。我们能做的是在两者之间找到最佳权衡。本章的目标就是建立分析这一权衡的数学工具。
反事实推理:如果没有通信延迟会怎样?回到 Goertz 的机械主从臂——钢丝绳的信号传播速度是声速(~5000 m/s),3 m 距离的延迟仅 0.6 ms,对人类感知完全不可察觉。透明度和稳定性可以同时完美实现。延迟是电控遥操作引入的**根本新问题**——没有延迟,二端口网络理论的大部分内容都不需要。
2. 二端口网络模型——从电路到遥操作 ⭐⭐¶
2.1 端口变量映射¶
二端口网络模型源自微波电路理论,由 Hannaford (1989) 引入遥操作领域。核心思想是将遥操作系统视为一个"黑盒"——两个端口分别连接操作者和环境,通过端口变量(力和速度)描述系统行为。
电气-力学类比:
| 电气量 | 力学量 | 符号 | 单位 |
|---|---|---|---|
| 电压 V | 力 f | \(f\) | N |
| 电流 I | 速度 v | \(v\) | m/s |
| 功率 P = VI | 功率 P = fv | \(P\) | W |
| 阻抗 Z = V/I | 阻抗 Z = f/v | \(Z\) | Ns/m |
被动符号约定:功率写成 \(P=f\cdot \nu\),其中 \(\nu\) 是**流入网络的端口速度**,流入网络为正。这一约定对后续的无源性分析至关重要。注意:图中的 \(v_m, v_s\) 是遥操作文献常用的物理速度方向;真正做无源性记账时要用 \(\nu_1=V_m,\ \nu_2=-V_s\)。
二端口网络拓扑
══════════════════════════════════════════
端口 1 (操作者侧) 端口 2 (环境侧)
┌────────────┐
f_h ────→ │ │ ←──── f_e
│ 遥操作系统 │
v_m ←──── │ (黑盒 H) │ ────→ v_s
│ │
└────────────┘
端口 1: (f_h, v_m)
f_h = 人手施加在 master 上的力
v_m = master 端速度
端口 2: (f_e, v_s)
f_e = 环境施加在 slave 上的力
v_s = slave 端速度
注意符号: f_h 指向网络内(操作者推 master)
f_e 指向网络内(环境推 slave)
v_m, v_s 是物理运动正方向
端口流入速度取 ν_1 = V_m, ν_2 = -V_s
2.2 混合参数 h——Hannaford 的统一框架 ⭐⭐¶
Hannaford (1989) 选择了混合参数 (h-parameters) 来描述遥操作系统,而非更常见的 Z 参数或 Y 参数。这一选择不是随意的。
混合参数矩阵定义:
注意输出向量中 \(V_s\) 带负号——这是被动符号约定的结果,使得两端口都用“流入网络”的速度变量记账:端口 1 为 \(V_m\),端口 2 为 \(-V_s\)。
h 参数的物理含义:
| 参数 | 测量条件 | 物理含义 |
|---|---|---|
| \(h_{11}(s) = F_h / V_m \big\|_{F_e=0}\) | 环境断开(自由空间) | Master 自由空间阻抗 |
| \(h_{12}(s) = F_h / F_e \big\|_{V_m=0}\) | Master 固定 | 力反射比(力传递效率) |
| \(h_{21}(s) = -V_s / V_m \big\|_{F_e=0}\) | 环境断开 | 运动传递比(位置跟踪) |
| \(h_{22}(s) = -V_s / F_e \big\|_{V_m=0}\) | Master 固定 | Slave 导纳 |
为什么选 h 参数而非 Z 或 Y?
Z 参数定义: [F_h; F_e] = Z * [V_m; V_s]
→ 两个端口都以速度为输入、力为输出
→ 问题: 实际系统中, master 端通常输入力(操作者推),
slave 端通常输出速度(跟随运动)
→ Z 参数不匹配实际因果关系
Y 参数定义: [V_m; V_s] = Y * [F_h; F_e]
→ 两个端口都以力为输入、速度为输出
→ 同样不匹配
h 参数: [F_h; -V_s] = H * [V_m; F_e]
→ 端口1: 速度输入, 力输出 (操作者速度 → master 反馈力)
→ 端口2: 力输入, 速度输出 (环境力 → slave 速度)
→ 完美匹配遥操作的因果关系!
"不是 X 而是 Y"纠正:很多教材从 Z 参数或散射参数入手介绍遥操作理论。但 Hannaford 选择 h 参数不是出于数学方便,而是因为 h 参数**直接对应遥操作系统的物理因果结构**——master 端是力源(阻抗因果),slave 端是运动源(导纳因果)。混合参数"混合"的正是这两种因果关系。
2.3 h 参数的完整推导——从基尔霍夫到传递矩阵 ⭐⭐⭐¶
为了真正理解 h 参数,我们需要从最基本的电路方程出发,经过 Z 参数和传递矩阵 T,最终推导出 h 参数。这一推导链揭示了各种参数化之间的深层关系。
Step 1:从基尔霍夫定律出发
考虑一个线性二端口网络。对端口 1 和端口 2 分别应用基尔霍夫电压/电流定律,网络内部的线性关系可以用四个独立参数描述。根据选择哪两个量作为自变量,得到不同的参数化。
Step 2:Z 参数(阻抗参数)——两个速度为输入
测量方法: - \(z_{11} = F_1/V_1 \big|_{V_2=0}\):端口 2 短路(速度为零=固定),从端口 1 看到的阻抗 - \(z_{12} = F_1/V_2 \big|_{V_1=0}\):端口 1 固定,端口 2 的速度如何引起端口 1 的力
Step 3:Y 参数(导纳参数)——两个力为输入
\(Y = Z^{-1}\)(前提是 \(\det(Z) \neq 0\))。
Step 4:传递矩阵 T(ABCD 参数)——级联最方便
传递矩阵的核心优势:级联。两个二端口网络串联时,总 T = T₁ · T₂,就像变换矩阵的级联。对于遥操作系统:
其中 \(T_{channel}\) 编码了通信通道(包括延迟)的效应。
Step 5:Z → h 的推导
从 Z 参数方程出发,将 \((V_1, F_2)\) 作为自变量重新整理:
第一行:\(F_1 = z_{11} V_1 + z_{12} V_2\)
第二行:\(F_2 = z_{21} V_1 + z_{22} V_2\) → 解出 \(V_2 = (F_2 - z_{21} V_1)/z_{22}\)
代入第一行:
同时由 \(V_2 = (F_2 - z_{21} V_1)/z_{22}\) 可得:
但本章 h 参数的标准形式是
因此必须对第二行取负号:
读出系数:
Step 6:T → h 的推导
从传递矩阵 \([F_1; V_1] = [A, B; C, D] [F_2; V_2]\) 重新整理:
第二式解出 \(V_2 = (V_1 - CF_2)/D\)。代入第一式:
因此:
各参数化的适用场景总结:
| 参数化 | 自变量 | 最适场景 | 遥操作中的角色 |
|---|---|---|---|
| Z(阻抗) | \((V_1, V_2)\) | 阻抗分析 | 环境耦合分析 |
| Y(导纳) | \((F_1, F_2)\) | 导纳分析 | 力控架构分析 |
| T(传递) | \((F_2, V_2)\) | 级联系统 | Master-channel-slave 级联 |
| h(混合) | \((V_1, F_2)\) | 混合因果 | 遥操作标准(因果匹配) |
| S(散射) | 入射波 | 波域分析 | 无源性分析(D06) |
本质洞察:所有五种参数化描述的是**同一个系统**——它们之间的转换不丢失任何信息。选择哪种参数化取决于分析目的。Hannaford 选择 h 参数是因为它直接对应遥操作的因果结构;Anderson-Spong 选择 S 参数是因为它直接表述无源性条件。理解这些参数化之间的关系,就是理解遥操作理论的"统一语言"。
散射参数 S ↔ h 参数(D06 将详细讨论):
散射参数 \(S\) 定义入射波和反射波的关系。\(\|S\|_\infty \leq 1\) 等价于端口被动性。h 参数和 S 参数之间的转换通过波阻抗 \(b\) 参数化——散射变换的奠基工作是 Anderson-Spong 1989(将散射理论引入遥操作,证明常数时延下的无源性),而"波变量"(wave variables)这一术语和传输线物理直觉的系统化则归功于 Niemeyer-Slotine 1991。
2.4 操作者感受阻抗 \(Z_{to}\) ⭐⭐¶
\(Z_{to}\)(transmitted-to-operator impedance)是衡量透明度的核心量——它描述操作者通过遥操作系统"感受到"的等效阻抗。
推导:
环境的阻抗关系:\(F_e = Z_e \cdot V_s\)
将 \(F_e = Z_e V_s\) 代入 h 参数方程:
从第二行:\(-V_s = h_{21} V_m + h_{22} F_e = h_{21} V_m + h_{22} Z_e V_s\)
因此:\(F_e = Z_e V_s = \frac{-h_{21} Z_e V_m}{1 + h_{22} Z_e}\)
从第一行:\(F_h = h_{11} V_m + h_{12} F_e\)
代入 \(F_e\):
也可以等价地写为:
其中 \(\Delta_h = h_{11} h_{22} - h_{12} h_{21}\) 是 h 矩阵的行列式。
各项的物理解释:
- \(h_{11}\):即使没有环境(\(Z_e = 0\)),操作者也会感受到 master 自身的阻抗(惯量、摩擦)
- \(\frac{h_{12} h_{21} Z_e}{1 + h_{22} Z_e}\):环境阻抗 \(Z_e\) 经过力反射和运动传递"穿透"遥操作系统后的等效值
- \(\Delta_h\):h 矩阵行列式,决定了高频环境阻抗的传递增益
特殊环境下的 \(Z_{to}\):
| 环境 | \(Z_e\) | \(Z_{to}\) | 理想值 |
|---|---|---|---|
| 自由空间 | \(0\) | \(h_{11}\) | \(0\) |
| 纯弹簧 | \(K/s\) | \(h_{11} - h_{12}h_{21}K/(s + h_{22}K)\) | \(K/s\) |
| 刚墙 | \(\infty\) | \((h_{11} h_{22} - h_{12} h_{21})/h_{22} = \Delta_h / h_{22}\) | \(\infty\) |
2.5 理想透明度的严格定义 ⭐⭐¶
定义(Lawrence 1993):遥操作系统是**理想透明**的,当且仅当:
这意味着操作者感受到的阻抗完全等于环境阻抗——如同直接触碰环境,遥操作系统"消失"了。
推导理想 H 矩阵:
令 \(Z_{to} = Z_e\) 对任意 \(Z_e\) 成立。将 \(Z_{to}\) 的表达式 \(\frac{h_{11} + \Delta_h Z_e}{1 + h_{22} Z_e} = Z_e\) 展开:
这必须对所有 \(Z_e\) 成立,因此各次幂系数必须分别相等:
- 常数项(\(Z_e^0\)):\(h_{11} = 0\)
- 一次项(\(Z_e^1\)):\(\Delta_h = 1\),即 \(h_{11} h_{22} - h_{12} h_{21} = 1\)
- 二次项(\(Z_e^2\)):\(h_{22} = 0\)
结合 \(h_{11} = 0, h_{22} = 0\):\(-h_{12} h_{21} = 1\)
最简解:\(h_{12} = 1, h_{21} = -1\)
物理验证:
- \(h_{11} = 0\):自由空间中 master 阻抗为零——操作者不感受 master 自身的惯量和摩擦
- \(h_{22} = 0\):slave 导纳为零——master 固定时 slave 不受环境力影响
- \(h_{12} = 1\):环境力 \(F_e\) 被 100% 传递到操作者
- \(h_{21} = -1\):master 速度 \(V_m\) 被 100% 传递到 slave(负号是符号约定)
代入 \(Z_{to}\) 公式验证:
本质洞察:理想透明度要求 \(h_{11} = h_{22} = 0\)——master 和 slave 的"自身存在"完全消失。但实际系统中,电机有惯量、齿轮有摩擦、控制器有延迟——这些都使得 \(h_{11}, h_{22} \neq 0\)。透明度的物理本质是让遥操作系统在操作者看来"不存在",但任何物理实体都不可能真正"不存在"。
⚠️ 常见陷阱¶
💡 概念误区:认为"理想透明度"意味着"力和速度都完美跟踪"
新手想法:"f_h = f_e 且 v_m = v_s → 完美透明"
实际上:仅力和速度匹配不够——还需要匹配"阻抗关系"
考虑一个标量增益系统: f_h = 2f_e, v_s = 2v_m
→ 力和速度都不匹配,但 Z_to = f_h/v_m = 2f_e/(2v_m)
→ 需要知道 F_e = Z_e V_s 代入才能判断
→ 实际上这个系统不一定透明,取决于缩放因子的一致性
正确理解:透明度定义的是阻抗匹配 Z_to = Z_e,
它是一个比信号匹配更本质的条件
🧠 思维陷阱:认为"提高控制带宽就能提高透明度"
新手想法:"更快的控制器 → 更好的跟踪 → 更高的透明度"
实际上:提高带宽确实能改善低频透明度,但:
(a) 高带宽控制器更容易不稳定(Bode 增益裕度限制)
(b) 采样-保持效应在高频引入额外相位滞后
(c) 传感器噪声在高频被放大
正确思维:透明度和稳定性的 trade-off 不是可以通过"更好的控制器"
消除的——它是系统级的物理限制
练习¶
- [A 型 -- h 参数计算] 对一个简单的 1-DOF 系统:master(质量 \(M_m = 0.5\) kg,阻尼 \(B_m = 2\) Ns/m)通过 PD 控制耦合 slave(质量 \(M_s = 1\) kg,阻尼 \(B_s = 1\) Ns/m),位置跟踪 + 力反射。写出 \(h_{11}, h_{12}, h_{21}, h_{22}\) 的传递函数表达式。用 \(Z_e = K_e/s\)(弹簧环境)画出 \(Z_{to}(j\omega)\) 的 Bode 图,观察与 \(Z_e\) 的偏差
- [思考题] 为什么 Lawrence 选择用阻抗 \(Z_{to}\) 而非力跟踪误差 \(|f_h - f_e|\) 定义透明度?提示:考虑一个缩放系统 \(f_h = 10 f_e, v_s = v_m/10\)——力误差很大,但操作者的阻抗感受如何?
3. Llewellyn 绝对稳定性准则 ⭐⭐⭐¶
3.1 为什么需要"绝对稳定性"¶
遥操作系统必须在所有可能的环境和操作者条件下保持稳定——我们不能假设操作者总是"配合的"或环境总是"温柔的"。
场景分析:
| 场景 | 操作者阻抗 \(Z_h\) | 环境阻抗 \(Z_e\) | 稳定性挑战 |
|---|---|---|---|
| 紧握 master + 刚墙 | 高(手臂刚度 ~2000 N/m) | 极高(\(>10^6\) N/m) | 高环路增益→振荡 |
| 松握 master + 自由空间 | 低(~50 N/m) | 零 | 低阻尼→超调 |
| 手指轻触 + 弹性物体 | 中等 | 中等 | 阻抗匹配差→能量积累 |
| 突然放手 + 碰撞 | \(0 \to \infty\) | \(0 \to \infty\) | 瞬态非线性→失稳 |
**绝对稳定性**要求系统在所有这些场景(以及它们之间的任意组合)下都保持稳定。
定义:h-二端口网络是**绝对稳定**的,当且仅当:对任意被动终端 \(Z_h\)(操作者)和 \(Z_e\)(环境),闭环系统 BIBO 稳定。
"被动终端"限制了 \(Z_h, Z_e\) 必须是被动的(不产生能量)——这是合理的物理假设(人和环境都不是能量源,从端口角度看)。
3.2 Llewellyn 准则的完整陈述 ⭐⭐⭐¶
定理(Llewellyn 1952,原用于微波电路,被 Lawrence 1993 引入遥操作):
h-二端口网络在任意被动负载下绝对稳定的**充要条件**为以下四项同时成立:
每个条件的物理意义:
| 条件 | 数学要求 | 物理含义 |
|---|---|---|
| L1 | \(h_{11}, h_{22}\) 稳定 | Master 和 slave 各自内部稳定 |
| L2 | \(\text{Re}\{h_{11}\} \geq 0\) | Master 端对操作者是被动的(不向操作者注入能量) |
| L3 | \(\text{Re}\{h_{22}\} \geq 0\) | Slave 端对环境是被动的(不向环境注入能量) |
| L4 | \(\eta(\omega) \geq 0\) | 系统的耗散大于互耦合引入的能量 |
为什么 L4 是核心条件:
L2 和 L3 保证了每个端口独立是被动的,但这不够——两个独立被动的端口通过反馈耦合后可能产生能量!L4 的作用正是限制这种耦合不能过强。
跨领域类比:L4 类似于电路中的振荡条件。一个运放(非被动元件)加上一个反馈网络(被动元件)可以构成振荡器——虽然反馈网络本身不产生能量,但与运放的正反馈组合可以从电源汲取能量并维持振荡。L4 确保遥操作系统中的"耦合"不会产生类似的正反馈振荡。
3.3 Llewellyn 准则的完整证明 ⭐⭐⭐⭐¶
理解 Llewellyn 准则不仅需要知道四个条件,更需要知道它们是**怎么被推导出来的**——这样才能在非标准场景下灵活应用。
证明思路:绝对稳定性要求对任意被动终端 \(Z_h, Z_e\)(\(\text{Re}\{Z_h\}, \text{Re}\{Z_e\} \geq 0\)),闭环系统 BIBO 稳定。我们将通过端口功率分析,推导出 h 参数必须满足的条件。
Step 1:闭环方程
操作者端:\(F_h = -Z_h V_m\)(负号因为操作者阻抗与端口被动符号相反——操作者"推"进系统)
环境端:\(F_e = Z_e V_s\)
代入 h 参数方程 \([F_h; -V_s] = H [V_m; F_e]\):
从第二式:\(V_s(1 + h_{22} Z_e) = -h_{21} V_m\),即 \(V_s = -h_{21} V_m / (1 + h_{22} Z_e)\)
代入第一式:
BIBO 稳定要求这个特征方程没有右半平面零点——对**所有** \(\text{Re}\{Z_h\}, \text{Re}\{Z_e\} \geq 0\)。
Step 2:条件 L1 的推导
如果 \(h_{11}(s)\) 或 \(h_{22}(s)\) 有右半平面极点,则当 \(Z_h = 0, Z_e = 0\)(即两端短路——自由空间+松手)时,闭环特征方程退化为 \(h_{11} \cdot 1 = 0\),而 \(h_{11}\) 的 RHP 极点使响应发散。因此 L1 是必要的。
Step 3:条件 L2, L3 的推导
取 \(Z_e = 0\)(自由空间),闭环变为:
稳定性要求 \(Z_h + h_{11}\) 没有 RHP 零点。对任意 \(\text{Re}\{Z_h\} \geq 0\),要使 \(Z_h + h_{11} \neq 0\),必须 \(h_{11} \neq -Z_h\)。特别地,\(h_{11}(j\omega)\) 不能是纯负实数——即 \(\text{Re}\{h_{11}(j\omega)\} \geq 0\)。
类似地,取 \(Z_h \to \infty\)(操作者完全固定),得到 L3:\(\text{Re}\{h_{22}(j\omega)\} \geq 0\)。
Step 4:条件 L4 的推导——核心步骤
L1-L3 只考虑了终端的极端情况(\(Z_e = 0\) 或 \(Z_h \to \infty\))。对一般的 \(Z_h, Z_e\),需要更强的条件。
对特征方程在 \(s = j\omega\) 处分析。令 \(Z_h = R_h + jX_h\),\(Z_e = R_e + jX_e\)(\(R_h, R_e \geq 0\))。
展开特征方程的实部和虚部,要求对任意 \(R_h, R_e \geq 0\) 和任意 \(X_h, X_e\) 都不能同时为零(否则有纯虚根→不稳定)。
经过代数运算(将 \(h_{ij}\) 分解为实虚部,展开乘积,收集关于 \(R_h R_e, R_h X_e, X_h R_e, X_h X_e\) 的项),稳定性条件等价于:
除以 \(|h_{12} h_{21}|\)(假设非零)并减 1,得到:
证明完毕 \(\blacksquare\)
证明的关键洞察:
- L1 来自"两端开路"的极端情况
- L2, L3 来自"一端开路、一端短路"的极端情况
- L4 来自"两端都是一般被动阻抗"的完整情况
- 四个条件是**充要的**——不存在更弱的替代条件
反事实推理:如果 L4 不是必要条件——即存在某个 \(\eta < 0\) 但仍绝对稳定的系统——那么证明第四步中的代数推导必有错误。但我们可以反方向验证:对任何 \(\eta(\omega_0) < 0\) 的系统,可以构造具体的被动终端 \(Z_h(\omega_0), Z_e(\omega_0)\) 使闭环在 \(\omega_0\) 处振荡。这证实了 L4 的必要性。
3.4 Llewellyn 准则的直觉理解 ⭐⭐¶
为了帮助建立直觉,让我们从能量角度重新解释 \(\eta\)。
考虑在频率 \(\omega\) 处,两个端口的功率流:
- 端口 1 流入功率:\(P_1 = \frac{1}{2} \text{Re}\{F_h V_m^*\} = \frac{1}{2} \text{Re}\{h_{11}\} |V_m|^2 + \frac{1}{2} \text{Re}\{h_{12} F_e V_m^*\}\)
- 端口 2 流入功率:\(P_2 = \frac{1}{2} \text{Re}\{F_e (-V_s)^*\}\)
绝对稳定性要求总功率流入非负(网络耗散能量而非产生能量):\(P_1 + P_2 \geq 0\)。
\(\eta(\omega) \geq 0\) 正是这一条件的等价表述——它确保在所有频率上,网络消耗的能量(\(\text{Re}\{h_{11}\} |V_m|^2 + \text{Re}\{h_{22}\} |V_s|^2\) 项)大于互耦合传递的能量(\(\text{Re}\{h_{12} h_{21}\}\) 项)。
3.5 透明度-稳定性 Trade-off 的数学证明 ⭐⭐⭐¶
这是本章最核心的结论——理想透明度与绝对稳定性在数学上存在根本性矛盾。
证明:
对理想透明度 \(H_{ideal}\):\(h_{11} = 0, h_{22} = 0, h_{12} = 1, h_{21} = -1\)
检查 Llewellyn 条件:
- L1: \(h_{11} = 0, h_{22} = 0\) 无极点 → 满足
- L2: \(\text{Re}\{0\} = 0 \geq 0\) → 满足(边界上)
- L3: \(\text{Re}\{0\} = 0 \geq 0\) → 满足(边界上)
- L4: 计算 \(\eta\)
工程含义:
\(\eta = 0\) 意味着系统虽然"名义上满足稳定条件",但任何微小扰动都可能使 \(\eta < 0\),导致不稳定。这些扰动在实际中不可避免:
| 扰动来源 | 对 \(\eta\) 的影响 |
|---|---|
| 通信延迟 \(T > 0\) | 引入 \(e^{-sT}\) → \(\text{Re}\{h_{12}h_{21}\}\) 变化 → \(\eta\) 可能变负 |
| 电机惯量 | \(h_{11} \neq 0\) 但有相位→可能使 \(\text{Re}\{h_{11}\} < 0\) 在某些频率 |
| 传感器噪声 | 等效于注入能量 → 破坏被动性 |
| 量化效应 | 离散化引入非线性 → Llewellyn(LTI)分析不适用 |
透明度-稳定性连续体
══════════════════════════════════════════
├──────────────────────────────────────┤
eta >> 0 eta = 0
高稳定性 完美透明
低透明度 零鲁棒裕度
(加很多阻尼) (无法实现)
工程可用区域 <======> 理论上限
如何获得正的 \(\eta\)?
增大 \(\text{Re}\{h_{11}\}\) 和 \(\text{Re}\{h_{22}\}\)——物理上对应在 master 和 slave 端增加本地阻尼:
对理想透明度的偏离(\(h_{12} h_{21} = -1\)):
只需 \(b_m, b_s > 0\)(无论多小),\(\eta' > 0\)。但代价是 \(Z_{to} \neq Z_e\)——操作者会感受到额外的粘滞感。
双重解读: - 角度 1(控制论):透明度-稳定性 trade-off 是 Bode 灵敏度积分约束的力学版本。Bode 定理说"灵敏度函数在某些频率减小必然在其他频率增大";这里的约束是"阻抗匹配的改善必然以鲁棒裕度为代价" - 角度 2(热力学):无额外阻尼的理想遥操作系统是"可逆的"(\(\eta = 0\)),就像卡诺热机效率最高但不可实现。加阻尼使系统变为"不可逆的"(\(\eta > 0\)),牺牲效率(透明度)换取可靠性(稳定性)
3.6 时延对 Llewellyn 条件的定量影响 ⭐⭐⭐¶
当 master 和 slave 之间存在通信延迟 \(T\) 时,情况急剧恶化。
延迟对 h 参数的影响:
假设一个 PD 位置跟踪 + 力反射架构,无延迟时:
加入往返延迟 \(T\)(每个方向 \(T/2\)):
在频率域:
关键频率:当 \(\omega T = \pi\)(即 \(\omega = \pi/T\))时:
代入 \(\eta\):
要 \(\eta \geq 0\):
阻尼的乘积必须大于控制增益的乘积——在大延迟下要求极高的阻尼。
数值示例(\(|C_f C_p| = 1\), \(b_m = b_s = b\)):
| 延迟 T | 需要的 \(b_{min}\) | 操作感受 |
|---|---|---|
| 1 ms | 1.0 Ns/m | 轻微阻尼 |
| 10 ms | 1.0 Ns/m | 同上(低频不受影响) |
| 100 ms | 1.0 Ns/m | 但高频 \(\eta\) 在 \(\omega = 31.4\) rad/s 处临界 |
| 500 ms | 1.0 Ns/m | 高频 \(\eta\) 在 \(\omega = 6.3\) rad/s 处临界 |
| 1000 ms | 1.0 Ns/m | \(\omega = 3.14\) rad/s 处临界——手动操作频段已受影响 |
关键观察:延迟不改变需要的阻尼量级(对固定增益),但**降低了临界频率**——当临界频率落入人手操作频段(1-10 Hz),系统在正常操作中就可能不稳定。
这就是为什么需要 D06 的波变量和 D07 的 TDPA——它们提供了在有延迟条件下保持被动性的方法,不依赖于增大阻尼。
⚠️ 常见陷阱¶
💡 概念误区:认为"Llewellyn 准则是保守的"
新手想法:"Llewellyn 要求任意被动负载下稳定 → 太严格了 → 实际不需要"
实际上:Llewellyn 准则是充要条件(不是仅充分!)
如果违反了 Llewellyn 条件,必定存在某个被动负载使系统不稳定
而人手阻抗在 50-5000 N/m 范围变化(松握→紧握)
环境从自由空间(Z_e=0)到刚墙(Z_e→∞)
→ 实际工况完全覆盖了"任意被动负载"的条件空间
🧠 思维陷阱:认为"加大增益就能提高透明度"
新手想法:"h₁₂ = 1 意味着力 100% 传递 → 增大力控增益让 h₁₂ → 1"
实际上:增大 |h₁₂| 会增大 |h₁₂h₂₁|,使 Llewellyn eta 更难满足
→ 需要更大的阻尼来补偿 → 透明度不升反降
正确思维:透明度不能通过简单增大增益提高
必须同时考虑稳定性约束——这就是 trade-off 的含义
练习¶
- [A 型 -- Llewellyn 计算] 对一个 1-DOF PP 架构(\(K_m\) 弹簧耦合 master-slave,加本地阻尼 \(b_m, b_s\)),推导 \(h_{11}, h_{12}, h_{21}, h_{22}\)。绘制 \(\eta(\omega)\) 曲线。找到使 \(\eta(\omega) \geq 0 \; \forall \omega\) 的最大 \(K_m\)
- [B 型 -- Lawrence 1993 精读] 精读 Section III-IV。手推四通道架构的 \(Z_{to}(s)\) 表达式。验证当 \(C_1=Z_{cs}, C_3=Z_{cm}, C_2=1+C_5, C_4=1+C_6\) 时 \(Z_{to} \equiv Z_e\)
- [思考题] 为什么深空遥操作(地月 1.3 s 延迟、地火 4-24 min 延迟)完全放弃了 bilateral 力反馈?用 Llewellyn 准则定量分析:\(T = 2.6\) s(往返)时需要什么样的阻尼?
4. 四种子架构——PP/PF/FP/FF ⭐⭐¶
4.1 四通道架构总览¶
Hannaford (1989) 将遥操作控制器分解为四个独立通道:
四通道架构
══════════════════════════════════════════
C₁(位置前馈)
v_m ─────────────────────→ slave 控制器
C₃(力前馈)
f_h ─────────────────────→ slave 控制器
↓
master 控制器 ←───────────── f_e
C₄(力反馈)
master 控制器 ←───────────── v_s
C₂(位置反馈)
C₁: master 速度 → slave 运动指令(位置通道,m→s)
C₂: slave 速度 → master 力指令(位置反馈通道,s→m)
C₃: master 力 → slave 力指令(力通道,m→s)
C₄: slave 力 → master 力指令(力反馈通道,s→m)
通过选择性地开启/关闭这四个通道,得到四种子架构。
4.2 PP 架构(位置-位置) ⭐⭐¶
特征:只用 \(C_1\) 和 \(C_2\)(位置通道),\(C_3 = C_4 = 0\)(无力通道)。
PP 架构: 两端都用位置控制器
━━━━━━━━━━━━━━━━━━━━━━━━━━━━━
Master: 位置控制器跟踪 x_s(slave 位置反馈)
Slave: 位置控制器跟踪 x_m(master 位置指令)
→ Master 和 slave 通过"虚拟弹簧"耦合
→ 等效于一个弹簧-阻尼连接
h 参数(二端口本体,不含环境终端):
注意这里不能写入 \(Z_e\)。\(H(s)\) 描述的是遥操作二端口本体;环境阻抗 \(Z_e\) 是接到端口 2 的终端,只能在后续计算操作者感受阻抗
时出现。若某个“h 矩阵”公式里直接含有 \(Z_e\),它描述的已经是接上特定环境后的闭环,而不是二端口参数。
优势与劣势:
| 优势 | 劣势 |
|---|---|
| 不需要力传感器 | 刚墙接触时残余弹性感("软墙") |
| 天然稳定(位置控制是被动的) | 不透明(\(h_{11}, h_{22} \neq 0\)) |
| 实现最简单 | 无法传递接触力的高频内容 |
| 对延迟鲁棒 | 自由空间有残余阻尼感 |
ALOHA 是哪种架构?
回顾 D04:ALOHA 是**退化的 PP 架构**——leader(master) 端无任何传感,只有位置编码器;follower(slave) 端只接收位置指令。严格来说不是 bilateral(无力反馈回 master),而是 unilateral position mapping:只有 \(C_1\) 通道打开,\(C_2 = C_3 = C_4 = 0\)。
4.3 PF 架构(位置→slave,力←master) ⭐⭐¶
特征:用 \(C_1\)(位置 m→s)和 \(C_4\)(力反馈 s→m),\(C_2 = C_3 = 0\)。
PF 架构:
━━━━━━━━━━━━━━━━━━━━━━━━━━━━━
Master: 导纳控制——接收 f_e 反馈,计算期望速度
Slave: 位置控制——跟踪 x_m(master 运动指令)
力传感器: 仅在 slave 端(测量 f_e)
优势与劣势:
| 优势 | 劣势 |
|---|---|
| 自由空间表现好(master 低阻抗) | 残余惯量感(\(h_{11} \approx Z_{cm}\)) |
| 只需 slave 端力传感器 | 硬墙接触时力反馈有延迟 |
| 工业最常用的有力反馈架构 | 无法完全消除 master 自身阻抗 |
| 合理的透明度-稳定性平衡 | 需要稳定的力测量 |
**da Vinci 手术机器人**用的就是 PF 变体——slave 端有 6-DOF 力/力矩传感,master 端有力反馈致动器。但为安全考虑,力反馈被有意降级(只传递部分力信息),以确保 \(\eta > 0\) 的大裕度。
4.4 FP 和 FF 架构¶
FP 架构(力→slave,位置←master)在实践中**几乎不使用**——slave 端的力控在不确定接触环境中容易不稳定,且需要 master 端的力传感器(成本高但收益低)。
FF 架构(力-力)理论上最透明——两端都用力控制:
但工程上极难实现,因为:
| 困难 | 来源 | 后果 |
|---|---|---|
| 噪声敏感 | 力传感器噪声直接影响两端 | 需要极高信噪比的力传感 |
| 低频不稳定 | 力控的双积分动力学 | 位置漂移不可控 |
| 两端传感器 | 需要 master 和 slave 都装力传感器 | 成本翻倍 |
| 调参困难 | 四个通道的增益互相耦合 | 参数空间高维 |
4.5 四种架构的 h 矩阵推导与代码框架 ⭐⭐⭐¶
为了将理论落地,给出每种架构的 h 矩阵显式表达和 Python 仿真代码框架。
PP 架构的 h 矩阵推导:
设 master 端本地控制器 \(C_m(s)\),slave 端本地控制器 \(C_s(s)\)。PP 架构中,master 生成位置指令发送给 slave,slave 的位置反馈回传给 master:
在力-速度表示下,二端口本体的 h 参数应只由 master/slave 本地动力学、控制器和通信环节决定。用四个终端无关的闭环传递函数表示最清楚:
因此在 \([F_h;-V_s]=H[V_m;F_e]\) 约定下:
其中 \(Y_s^{cl}\) 是 slave 端位置闭环在 master 固定时对外力的导纳,\(G_{ms}^{cl}\) 是 master 到 slave 的速度跟踪传递函数。它们可以包含 slave 自身阻抗 \(Z_s\)、位置环 \(C_s\)、采样/延迟等二端口内部因素,但**不包含环境阻抗 \(Z_e\)**。接上具体环境后再把 \(F_e=Z_eV_s\) 代入 D5.2 的 \(Z_{to}\) 公式。
PF 架构的 h 矩阵推导:
slave 端位置控制 \(C_s\),master 端接收力反馈 \(f_e\) 并通过导纳控制器 \(Y_m = 1/Z_{cm}\) 输出速度:
Python 仿真代码框架:
import numpy as np
from scipy import signal
class TeleoperationArchitecture:
"""四种遥操作架构的统一仿真框架"""
def __init__(self, arch_type, dt=0.001,
Mm=0.5, Bm=2.0, Ms=1.0, Bs=1.0,
Kp=100.0, Kd=20.0, Kf=1.0):
self.arch = arch_type # 'PP', 'PF', 'FP', 'FF'
self.dt = dt
self.Mm, self.Bm = Mm, Bm
self.Ms, self.Bs = Ms, Bs
self.Kp, self.Kd, self.Kf = Kp, Kd, Kf
# 状态: [xm, vm, xs, vs]
self.state = np.zeros(4)
def step(self, f_human, f_env, delay_buffer_m2s, delay_buffer_s2m):
"""单步仿真——支持延迟缓冲"""
xm, vm, xs, vs = self.state
# === 根据架构选择通信信号 ===
if self.arch == 'PP':
# 只传位置
xs_delayed = delay_buffer_s2m.get() # slave→master
xm_delayed = delay_buffer_m2s.get() # master→slave
tau_m = self.Kp * (xs_delayed - xm) + self.Kd * (-vm)
tau_s = self.Kp * (xm_delayed - xs) + self.Kd * (-vs)
elif self.arch == 'PF':
# master→slave: 位置; slave→master: 力
xm_delayed = delay_buffer_m2s.get()
fe_delayed = delay_buffer_s2m.get()
tau_m = self.Kf * fe_delayed + self.Bm * (-vm)
tau_s = self.Kp * (xm_delayed - xs) + self.Kd * (-vs)
elif self.arch == 'FP':
# master→slave: 力; slave→master: 位置
fh_delayed = delay_buffer_m2s.get()
xs_delayed = delay_buffer_s2m.get()
tau_m = self.Kp * (xs_delayed - xm) + self.Kd * (-vm)
tau_s = fh_delayed + self.Bs * (-vs)
elif self.arch == 'FF':
# 两端都传力
fh_delayed = delay_buffer_m2s.get()
fe_delayed = delay_buffer_s2m.get()
tau_m = self.Kf * fe_delayed + self.Bm * (-vm)
tau_s = fh_delayed + self.Bs * (-vs)
# === 动力学积分 ===
am = (f_human + tau_m - self.Bm * vm) / self.Mm
a_s = (-f_env + tau_s - self.Bs * vs) / self.Ms
vm += am * self.dt
vs += a_s * self.dt
xm += vm * self.dt
xs += vs * self.dt
self.state = np.array([xm, vm, xs, vs])
# === 更新延迟缓冲 ===
if self.arch == 'PP':
delay_buffer_m2s.put(xm)
delay_buffer_s2m.put(xs)
elif self.arch == 'PF':
delay_buffer_m2s.put(xm)
delay_buffer_s2m.put(f_env)
elif self.arch == 'FP':
delay_buffer_m2s.put(f_human + tau_m)
delay_buffer_s2m.put(xs)
elif self.arch == 'FF':
delay_buffer_m2s.put(f_human + tau_m)
delay_buffer_s2m.put(f_env)
return self.state, tau_m, tau_s
def compute_h_matrix(self, omega_range):
"""计算 h 参数的频率响应"""
h = np.zeros((len(omega_range), 2, 2), dtype=complex)
for i, w in enumerate(omega_range):
s = 1j * w
Zm = self.Mm * s + self.Bm
Zs = self.Ms * s + self.Bs
C = self.Kp + self.Kd * s
if self.arch == 'PP':
h[i, 0, 0] = Zm + C * C / (C + Zs)
h[i, 0, 1] = C / (C + Zs)
h[i, 1, 0] = -C / (C + Zs)
h[i, 1, 1] = 1 / (C + Zs)
elif self.arch == 'PF':
h[i, 0, 0] = Zm
h[i, 0, 1] = self.Kf
h[i, 1, 0] = -C / (C + Zs)
h[i, 1, 1] = 1 / (C + Zs)
# ... FP, FF 类似
return h
def compute_eta(self, h):
"""计算 Llewellyn 稳定因子 eta(omega)"""
h11, h12, h21, h22 = h[:,0,0], h[:,0,1], h[:,1,0], h[:,1,1]
numerator = 2 * h11.real * h22.real - (h12 * h21).real
denominator = np.abs(h12 * h21) + 1e-15
return numerator / denominator - 1
4.6 四种架构的系统对比¶
| 架构 | \(h_{11}\) | \(h_{22}\) | 透明度 | 稳定性 | 力传感器 | 典型应用 |
|---|---|---|---|---|---|---|
| PP | \(\neq 0\) | \(\neq 0\) | 低 | 高 | 0 个 | ALOHA、学习数据采集 |
| PF | \(\neq 0\) | \(\approx 0\) | 中高 | 中 | 1 个(slave) | da Vinci、工业遥操作 |
| FP | \(\approx 0\) | \(\neq 0\) | 中 | 低 | 1 个(master) | 几乎不用 |
| FF | \(\approx 0\) | \(\approx 0\) | 最高 | 最低 | 2 个 | 研究实验室 |
反事实推理:如果 ALOHA 使用 PF 架构(加上 slave 端力传感器 + master 端力反馈)会怎样?从 Z-width 分析(第 5 节详述):50 Hz 采样下,\(K_{max} = 2b/T = 2 \times 2 / 0.02 = 200\) N/m。人手抓握刚度 ~2000 N/m——无法渲染出有意义的刚墙。力反馈在 50 Hz 下不可用,这是 ALOHA 放弃力反馈的又一定量理由。
4.7 Hashtrudi-Zaad & Salcudean (2001) 选型框架 ⭐⭐¶
不同的硬件接口自然适配不同的架构。Hashtrudi-Zaad 和 Salcudean 系统分析了**阻抗/导纳 master \(\times\) slave** 的四种组合:
| 组合 | Master 端 | Slave 端 | 适用场景 |
|---|---|---|---|
| I-I | 阻抗(力矩输出) | 阻抗(力矩输出) | 高带宽研究平台(如 Omega.7 + Franka) |
| I-A | 阻抗 | 导纳(位置输出) | 工业机器人 slave(KUKA/UR + 位置接口) |
| A-I | 导纳 | 阻抗 | 触觉设备 master + 直驱 slave |
| A-A | 导纳 | 导纳 | 工业标准(两端都是位置控制器) |
选型原则(回顾 F01 的阻抗/导纳因果性):
- 硬件提供力矩接口 → 阻抗因果(如 Franka 直驱关节)
- 硬件提供位置接口 → 导纳因果(如工业 KUKA + 运动控制器)
- **I-A 组合**是最常见的工业配置——haptic master(力矩输出)+ 工业 slave(位置输入)
⚠️ 常见陷阱¶
💡 概念误区:认为"四通道全开一定比两通道好"
新手想法:"PP 用 2 通道,四通道全开用 4 通道 → 信息更多 → 更好"
实际上:四通道全开(Lawrence 的理想四通道)需要精确匹配 6 个参数
才能实现理想透明度。任何参数失配都可能导致不稳定
两通道(PP/PF)虽然透明度有限,但鲁棒性高得多
正确思维:通道数不是"越多越好"——是"越多越难调"
工业系统偏好 PF(2-3 通道),因为可靠性优先
🧠 思维陷阱:认为"ALOHA 不做力反馈是因为便宜"
新手想法:"加个力传感器才几千块,ALOHA 省这点钱"
实际上:即使加了力传感器,50 Hz 下的 Z-width 也不足以渲染有用的力反馈
真正的瓶颈是控制频率和采样-保持效应,不是传感器成本
回顾 D04: 这是系统级 co-design 决策,不是简单的成本节约
练习¶
- [A 型 -- 架构对比仿真] 在 Python/MATLAB 中实现 1-DOF PP 和 PF 架构。对比两者在 (a) 自由空间 (b) 弹性墙 (\(K_e = 500\) N/m) (c) 刚性墙 (\(K_e = 50000\) N/m) 三种环境下的 \(Z_{to}\) Bode 图
- [跨章综合题] 用 D04 的 ALOHA 硬件参数(Dynamixel XM540、50 Hz Python、无力传感器),分析它可以实现四种架构中的哪些?不能实现的写出具体缺少什么硬件/能力。结合 F01 的阻抗/导纳因果性分析
- [B 型 -- h 参数仿真] 使用 4.5 节的
TeleoperationArchitecture代码框架,对四种架构分别计算 \(h\) 矩阵的频率响应(0.1-100 rad/s)。绘制 \(\text{Re}\{h_{11}\}\)、\(\text{Re}\{h_{22}\}\)、\(\eta(\omega)\) 三张图。哪种架构的 \(\eta\) 最大(最稳定)?哪种的 \(h_{11}, h_{22}\) 最接近零(最透明)?
5. Z-width——触觉设备的核心性能指标 ⭐⭐¶
5.0 Z-width 与遥操作系统设计的关系¶
Z-width 不仅是触觉设备的指标——它是遥操作系统"是否能做力反馈"的**第一道门槛**。在进入具体分析之前,用一张决策图说明 Z-width 在系统设计中的位置:
力反馈可行性判断流程
══════════════════════════════════
1. 测量硬件参数: b (物理阻尼), T_s (采样周期)
2. 计算 K_max = 2b/T_s
3. 确定目标环境刚度: K_env
4. K_max >= K_env?
├── 是 → Z-width 满足 → 可以做力反馈
│ → 继续选择架构 (PP/PF/FF)
└── 否 → Z-width 不足 → 两种选择:
├── (a) 提高采样频率 (硬件升级)
└── (b) 放弃力反馈 (如 ALOHA 的选择)
5.1 Z-width 的定义与物理意义¶
Z-width(Colgate and Brown 1994)是衡量触觉设备或遥操作系统性能的核心指标。
定义:在满足被动性(不向操作者注入能量)约束下,系统能渲染的阻抗范围 \([Z_{min}, Z_{max}]\)。
Z-width 示意图
══════════════════════════════════════════
阻抗轴: |──Z_min──────────────Z_max──|
Z_min: 自由空间阻抗(越低越好 → "无重力感")
理想: Z_min = 0 (完全自由)
实际: Z_min = M_motor * s + B_friction (电机惯量+摩擦)
Z_max: 最硬虚拟墙阻抗(越高越好 → "像真墙")
理想: Z_max = ∞ (完美刚墙)
实际: Z_max = 2b/T (被动性约束上限)
Z-width = Z_max / Z_min (越大越好)
5.2 虚拟墙被动条件——完整推导 ⭐⭐⭐¶
问题设置:1-DOF 系统,物理阻尼 \(b\),渲染虚拟弹簧 \(K\),采样周期 \(T\),零阶保持器(ZOH)。
连续时间虚拟墙:
离散实现(ZOH):
被动性条件推导:
系统是被动的当且仅当在任意运动中总流入能量非负:
考虑最恶劣情况的一个采样周期分析。在 \([kT, (k+1)T]\) 内,ZOH 保持 \(f = f[k] = Kx[k]\),但速度可以任意变化。
设时刻 \(kT\) 位置为 \(x[k] > 0\)(在墙内),速度突然反向:
- 前半周期 \([kT, kT + T/2]\):\(v = v_0 > 0\)(继续推入)
- 后半周期 \([kT+T/2, (k+1)T]\):\(v = -v_0\)(拉出)
这一周期内的能量变化:
由于 ZOH,\(f\) 在整个周期内恒定为 \(Kx[k]\)。速度积分(位移)为零。但能量积分不为零——因为位置在变化而力保持旧值。
经过精确分析(考虑物理阻尼的能量耗散 \(P_{diss} = b v^2\)),被动性条件为:
等价地:
推导中的关键物理洞察:ZOH 使力信号"延迟"了最多 \(T\)——在速度反转后力仍保持旧方向,产生了"力和速度方向相反"的时段,此时系统**向操作者注入能量**。物理阻尼 \(b\) 必须足够大以耗散这些注入的能量。
5.3 数值示例与工程意义 ⭐⭐¶
| 物理阻尼 \(b\) | 采样频率 | 采样周期 \(T\) | \(K_{max}\) | 人体感知 |
|---|---|---|---|---|
| 1 Ns/m | 100 Hz | 10 ms | 200 N/m | 软橡皮(不像墙) |
| 1 Ns/m | 1 kHz | 1 ms | 2000 N/m | 硬塑料(可接受) |
| 1 Ns/m | 4 kHz | 0.25 ms | 8000 N/m | 金属感(很好) |
| 1 Ns/m | 10 kHz | 0.1 ms | 20000 N/m | 刚墙(接近理想) |
关键发现:\(K_{max}\) 与采样频率成正比——采样率翻倍,Z-width 翻倍。
教学要点:Z-width 是理解"为什么力控必须高频"的又一个维度。回顾 F01:接触瞬态需要高频响应;这里的 Z-width 分析揭示了**即使没有接触瞬态,被动性约束本身就要求高采样率才能渲染高刚度**。
跨领域类比:Z-width 与音频设备的动态范围类似。音频的动态范围 = 最大音量 / 最小噪声底;Z-width = 最硬墙 / 最轻触感。就像 24-bit 音频比 16-bit 有更宽的动态范围(因为量化噪声更小),高频采样的触觉设备比低频有更宽的 Z-width(因为 ZOH 效应更小)。
5.4 虚拟墙无源性条件的频域分析 ⭐⭐⭐¶
时域分析给出了 \(b > KT/2\) 的必要条件,但频域分析可以揭示更多细节——特别是**在什么频率**被动性最先被违反。
离散虚拟墙的传递函数:
ZOH 虚拟墙在 z 域中的传递函数为:
等效阻抗(z 域):
在单位圆上 \(z = e^{j\omega T_s}\):
实部分析——被动性要求 \(\text{Re}\{Z_{wall}(e^{j\omega T_s})\} \geq 0\):
关键结果:\(\text{Re}\{Z_{wall}\} = -KT_s/2 < 0\),对**所有频率**。
这意味着纯 ZOH 虚拟弹簧在所有频率上都是**主动的**(注入能量)!物理阻尼 \(b\) 的作用是提供一个正的实部 \(b\) 来抵消这个负值:
这与时域分析的结果 \(b > KT/2\) 完全一致,但频域视角更清楚地揭示了**ZOH 在所有频率上均匀地注入能量**——不存在"安全频段"。
更多 Worked Examples:
Example 1:弹簧-阻尼虚拟墙
如果虚拟墙是 \(f = Kx + B\dot{x}\)(弹簧+阻尼),则虚拟阻尼 \(B\) 贡献额外的正实部:
虚拟阻尼 \(B\) **增加**了 \(K_{max}\)——允许渲染更硬的墙!代价是操作者在碰墙后会感受到粘滞感。
Example 2:惯性虚拟物体
虚拟惯性 \(f = M\ddot{x}\) 对应 \(Z_{virtual}(s) = Ms\)。ZOH 离散化后:
虚拟惯性是天然被动的(无需额外阻尼)!物理解释:惯性只储存动能不产生能量。但在 Nyquist 频率 \(\omega = \pi/T_s\) 附近,\(\text{Re}\) 趋近于零——说明高频处被动性余量最小。
Example 3:复合虚拟环境(弹簧+质量+阻尼)
被动性条件变为:
最恶劣频率在低频(\(\omega \to 0\) 时惯性项消失):\(b + B - KT_s/2 \geq 0\)
与 Example 1 相同——弹簧项决定了最恶劣条件。
5.5 Z-width 与 ALOHA 的定量分析¶
回顾 D04,现在可以用 Z-width 严格定量论证 ALOHA 不做力反馈的决定。
ALOHA 参数: - 控制频率 50 Hz → \(T = 20\) ms - Dynamixel 等效阻尼 \(b \approx 2\) Ns/m
人手抓握刚度 ~2000 N/m → \(K_{max}\) 比人手刚度低 10 倍。
即使 ALOHA 有力传感器和力反馈执行器,在 50 Hz 下也无法渲染出"有意义的刚墙"——操作者会感觉虚拟墙像棉花糖,这比没有力反馈更糟(误导操作者的力觉判断)。
⚠️ 常见陷阱¶
⚠️ 编程陷阱:ZOH 导致的虚拟墙不稳定
错误做法:在 100 Hz 渲染 K=5000 N/m 的虚拟墙
现象:接触虚拟墙时系统振荡→"嗡嗡响"→末端弹开
根本原因:K > K_max = 2*1/0.01 = 200 N/m → 违反被动性
正确做法:(a) 提高采样频率到 1 kHz+(b) 增加物理/虚拟阻尼 (c) 降低 K
自检方法:监测系统总能量 E(t),如果持续增加则被动性被违反
💡 概念误区:认为"只要虚拟墙不振荡就是稳定的"
新手想法:"我的虚拟墙看起来不振荡 → 一定满足被动性"
实际上:被动性是比"不振荡"更强的条件——
一个非被动系统在温和输入下可能表现良好,
但在极端输入(快速反复碰撞墙壁)下会注入能量并发散
被动性保证在任意操作下都不注入能量
正确做法:用被动性条件 b > KT/2 做理论校验,不要依赖经验观察
练习¶
- [A 型 -- Z-width 实验] 在 Python 中实现 1-DOF ZOH 虚拟墙。分别用 \(T = 1\) ms 和 \(T = 10\) ms。逐步增大 \(K\) 直到系统能量 \(E(t)\) 变负(被动性违反)。记录 \(K_{max}\) 并与理论值 \(2b/T\) 对比
- [思考题] 如果将虚拟墙从弹簧 \(f = Kx\) 改为弹簧-阻尼 \(f = Kx + B\dot{x}\),被动条件如何变化?虚拟阻尼 \(B\) 是增加还是减少了 \(K_{max}\)?
6. 从理论到工程——遥操作系统设计指南 ⭐⭐¶
6.1 系统选型决策树¶
根据本章理论,给出遥操作系统选型的工程决策流程:
延迟 T 是多少?
├── T < 5 ms(本地连接)
│ ├── 需要力反馈?
│ │ ├── 是 → PF/FF 架构 + 1-2 kHz 力控
│ │ └── 否 → PP 架构(ALOHA 方案)
│ └── Z-width 需求?
│ ├── 高(手术/精密装配)→ 4+ kHz 采样 + 低惯量 master
│ └── 低(数据采集/简单操作)→ 50-100 Hz 即可
├── T = 5-200 ms(局域网/5G)
│ ├── 波变量 + PF 架构(D06)
│ └── 或 TDPA 安全层(D07)
├── T = 200 ms - 2 s(互联网/卫星)
│ ├── 波变量 + TDPA 组合
│ └── 或 Model-Mediated Teleoperation
└── T > 2 s(深空)
└── 放弃 bilateral → Supervisory Control
6.2 遥操作系统设计完整流程图 ⭐⭐¶
将本章所有理论工具组织为一个完整的系统设计流程:
遥操作系统设计流程(从需求到参数)
═══════════════════════════════════════════════════════════════
Step 1: 需求分析
├── 任务类型: 精密装配 / 搬运 / 数据采集 / 探测
├── 延迟范围: 本地(<5ms) / LAN(5-50ms) / WAN(50-300ms) / 深空(>1s)
├── 力反馈需求: 必须(手术) / 期望(装配) / 可选(搬运) / 不要(采集)
└── 安全等级: 关键(手术/核处理) / 高(工业) / 一般(研究)
Step 2: 硬件选型
├── Master 设备 → 确定 Z_m (阻抗因果/导纳因果)
├── Slave 设备 → 确定 Z_s (阻抗因果/导纳因果)
├── 力传感器 → 确定力测量精度和带宽
└── 控制频率 → 确定 T_s (采样周期)
Step 3: Z-width 校验 (本章 5 节)
├── K_max = 2b/T_s → 最大可渲染刚度
├── K_max >= K_env (任务环境刚度)?
│ ├── 是 → Z-width 满足,继续
│ └── 否 → 提高采样频率 或 放弃力反馈
└── Z_min = M_motor * s + B_friction → 检查自由空间感受
Step 4: 架构选择 (本章 4 节)
├── 力传感器数量
│ ├── 0 → PP (如 ALOHA)
│ ├── 1 (slave) → PF (工业标准)
│ ├── 1 (master) → FP (罕用)
│ └── 2 → FF 或四通道 (研究级)
└── I/A 组合 → Hashtrudi-Zaad 选型表 (4.7 节)
Step 5: Llewellyn 稳定性校验 (本章 3 节)
├── 计算 h 矩阵 → h_{11}, h_{12}, h_{21}, h_{22}
├── 检查 L1-L3 (独立端口被动性)
├── 计算 eta(omega) → 绘制频率曲线
├── eta_min >= 0?
│ ├── 是 → 名义稳定
│ └── 否 → 增加本地阻尼 b_m, b_s → 重新计算
└── eta_min >= eta_margin (安全裕度)?
├── 是 → 设计完成
└── 否 → 降低控制增益 / 加阻尼 / 波变量(D06) / TDPA(D07)
Step 6: 延迟鲁棒性校验 (本章 3.6 节)
├── 加入目标延迟 T → 重新计算 eta(omega)
├── eta(omega=pi/T) >= 0?
│ ├── 是 → 延迟鲁棒,设计完成
│ └── 否 → 波变量(D06) / TDPA(D07) / 增大阻尼
└── 延迟 > 200 ms?
├── 是 → 强烈推荐波变量 + TDPA 组合
└── 否 → 可选使用
Step 7: 工程实现
├── 通信协议: UDP (低延迟) / TCP (可靠)
├── 实时内核: PREEMPT_RT / Xenomai
├── 安全层: TDPA (D07) 作为最终安全网
└── 诊断: 能量监测、延迟统计、力/位误差
设计流程的关键决策点:
| 决策点 | 输入 | 判据 | 输出 |
|---|---|---|---|
| Z-width 校验 | \(b, T_s, K_{env}\) | \(K_{max} \geq K_{env}\)? | 通过/提高频率/放弃力反馈 |
| 架构选择 | 力传感器数量+I/A 类型 | 查表 4.6/4.7 | PP/PF/FP/FF |
| Llewellyn 校验 | h 矩阵 | \(\eta_{min} \geq 0\)? | 通过/加阻尼 |
| 延迟校验 | \(T, h_{12}h_{21}\) | \(\eta(\pi/T) \geq 0\)? | 通过/加波变量/TDPA |
6.3 工业遥操作平台对比¶
| 平台 | 架构 | 延迟 | 力反馈 | 采样率 | 主要应用 |
|---|---|---|---|---|---|
| ALOHA | 退化 PP | <3 ms | 无 | 50 Hz | 学习数据采集 |
| da Vinci (Intuitive) | PF 变体 | <1 ms | 有(降级) | 1 kHz | 微创手术 |
| DLR KONTUR-2 | 四通道+TDPA | 10-30 ms | 有 | 1 kHz | 空间遥操作 |
| Omega.7 (Force Dimension) | I-I | <1 ms | 6-DOF 力 | 4 kHz | 触觉研究 |
| Geomagic Touch | A-A | ~2 ms | 3-DOF 力 | 1 kHz | 触觉教学 |
| Franka Panda + Omega.7 | I-I (PF) | 1-5 ms | 3-DOF 力 | 1 kHz | 双臂研究 |
| dVRK (da Vinci Research Kit) | PF + TDPA | <1 ms | 有 | 1 kHz | 手术机器人研究 |
| UR5 + SpaceMouse | 退化 PP | ~5 ms | 无 | 125 Hz | 工业数据采集 |
平台选型决策指南:
你的遥操作需求是什么?
│
├── 学习数据采集(不需要力反馈)
│ ├── 预算 < $10k → ALOHA (D04)
│ ├── 预算 $10-50k → Franka + 直接动觉教学
│ └── 需要移动 → Mobile ALOHA
│
├── 力反馈遥操作(需要触觉)
│ ├── 延迟 < 5 ms
│ │ ├── 高精度 → Omega.7 + Franka (PF)
│ │ └── 手术级 → dVRK
│ ├── 延迟 5-200 ms
│ │ ├── 推荐 → 波变量(D06) + TDPA(D07)
│ │ └── 硬件 → Omega.7 + UR5/Franka
│ └── 延迟 > 200 ms
│ ├── 推荐 → 波变量 + 能量罐 + TDPA
│ └── 备选 → Model-Mediated Teleoperation
│
└── 共享控制(部分自主)
├── da Vinci (Shared Control mode)
└── 自研系统 → D08 运动映射 + D09 MoveIt2
6.4 与 F01-F02 力控数学的接口¶
遥操作理论与 F01-F02 的力控理论密切相关。建立以下对应关系有助于知识迁移:
| F 系列概念 | 遥操作中的对应 | 联系点 |
|---|---|---|
| 阻抗控制 \(Z = F/V\) | 二端口 \(h_{11}\)(master 端阻抗) | F01 的阻抗概念直接用于遥操作 |
| 导纳控制 \(Y = V/F\) | 二端口 \(h_{22}\)(slave 端导纳) | F01 的导纳概念 |
| 无源性 \(\int fv \, dt \geq 0\) | Llewellyn 条件 L2, L3 | F02.4 的定义直接适用 |
| 能量观测器 | TDPA 的 Passivity Observer(D07) | F02.4 的能量分析工具 |
| 接触稳定性 | 操作者+系统+环境的耦合稳定 | F01 的环境耦合分析 |
7. 前沿工作与开放问题 ⭐⭐⭐¶
7.1 Model-Mediated Teleoperation ⭐⭐⭐¶
动机:当延迟超过 200 ms 时,即使使用波变量+TDPA,操作者感受到的力反馈也是"过时"的(延迟至少 200 ms)。人类对 >200 ms 的力延迟极其敏感——操作策略从"连续控制"退化为"move-and-wait"(Ferrell 1965)。
Hirche-Buss (2012) 提出了一种根本不同的方案——在 slave 侧建立环境模型,传输模型参数而非原始力信号。这个方案**绕过了延迟问题**,代价是模型精度决定了体验质量:
传统 bilateral:
slave → [f_e(t)] → 延迟 T → master
操作者感受: 延迟 T 前的力
Model-Mediated:
slave → [环境模型参数: K_e, B_e, x_wall] → 延迟 T → master
master 本地渲染: f_rendered = K_e(x_m - x_wall) + B_e * v_m
操作者感受: "低延迟"的力(模型渲染,非真实力)
优势:力渲染完全本地化,不受延迟影响。劣势:模型精度决定了体验质量。
Model-Mediated 的关键工程挑战:
| 挑战 | 详细说明 | 影响 |
|---|---|---|
| 模型辨识精度 | 环境刚度/阻尼的在线估计误差 | 力渲染偏差 → 操作者误判 |
| 模型切换 | 从自由空间到接触的模型切换 | 切换瞬间力不连续 |
| 非线性环境 | 凸多面体/软物体的非线性力学 | 线性模型不足 |
| 模型更新带宽 | 模型参数的传输频率 | 快速变化的环境跟不上 |
| 未建模动力学 | 摩擦/粘弹性等 | 长时间操作后偏差累积 |
跨领域类比:Model-Mediated 类似于视频通话中的"虚拟背景"——不传输真实背景像素(高带宽),而是传输一个参数化的背景模型(低带宽),在本地渲染。当真实背景简单时效果好,当背景复杂时(如大量运动物体)效果差。
7.2 Shared Autonomy 与遥操作的融合 ⭐⭐¶
现代遥操作越来越多地采用共享控制范式——D08 将详细讨论如何将遥操作与学习算法(D04 的 ACT/Diffusion Policy)结合:
- 操作者提供高级意图(移动方向)
- 自主系统处理低级控制(避碰、力控)
- 典型如 da Vinci 的 wristed instrument control
共享控制的数学框架:
其中 \(\alpha(t) \in [0, 1]\) 是"人类控制权"系数。\(\alpha = 1\) 退化为直接遥操作;\(\alpha = 0\) 退化为完全自主。
\(\alpha(t)\) 的设计原则:
| 场景 | \(\alpha\) | 理由 |
|---|---|---|
| 自由空间运动 | 0.3-0.5 | 自主系统处理路径平滑和避障 |
| 精细操作(接近目标) | 0.8-1.0 | 人类的灵巧判断最关键 |
| 危险区域(接近关节极限) | 0.1-0.3 | 自主系统保证安全 |
| 接触操作 | 0.5-0.7 | 人类控制意图+自主力控 |
与 D05 理论的关系:共享控制中 \(u_{auto}\) 是一个主动元件(它可以产生能量),这违反了 Llewellyn 分析中"被动终端"的假设。因此,共享控制系统的稳定性分析不能直接用 Llewellyn 准则——需要用 D07 的 TDPA 作为安全保证。
共享控制的安全层设计:
在共享控制中,TDPA 的 PO 监测人机混合系统的总端口能量。当 \(E_{obs} < 0\) 时,可能是自主系统的主动行为注入了过多能量。此时 PC 的介入不是"消灭有害能量",而是"限制自主系统的主动性"——通过缩放 \(u_{auto}\) 的增益来保证整体被动性。这是 TDPA 在非传统遥操作场景下的创新应用。
7.3 从 Llewellyn 到现代——二端口理论的局限与超越 ⭐⭐⭐¶
Llewellyn 准则建立于 1952 年微波电路理论,其核心假设是 LTI(线性时不变)。但现代遥操作系统中存在大量非线性和时变因素:
Llewellyn 准则的适用边界:
| 因素 | LTI 假设 | 实际系统 | 对 Llewellyn 的影响 |
|---|---|---|---|
| 采样-ZOH | 连续信号 | 离散+ZOH | 等效延迟,需修正 \(\eta\) |
| 接触/释放 | 线性 \(Z_e\) | 非线性切换 | Llewellyn 在切换瞬间不适用 |
| 摩擦 | 无 | 库仑+粘性 | 非线性→需 Lyapunov 分析 |
| RL 策略 | 线性控制器 | 非线性 NN | Llewellyn 完全不适用 |
| 自适应控制 | 时不变 | 参数在线更新 | 需 LTV 稳定性理论 |
超越 Llewellyn 的三条路径:
- 无源性方法(D06 波变量 / D07 TDPA):不要求 LTI,对非线性系统也适用。代价是条件更保守——无源性是比稳定性更强的要求
- Lyapunov 方法(Chopra-Spong-Lozano 2008):直接构造 Lyapunov 函数证明闭环稳定,无需 LTI 假设。但需要针对每种控制律单独设计 Lyapunov 函数
- 小增益定理(Zames 1966):将系统分解为互联子系统,通过各子系统的增益界限判断整体稳定性。适用于非线性系统但条件可能保守
"不是 X 而是 Y"纠正:Llewellyn 准则不是"过时的理论"——它是**在 LTI 范围内最精确的工具**(充要条件)。超越 LTI 的方法(无源性、Lyapunov、小增益)更通用但更保守(充分条件)。工程实践中,先用 Llewellyn 做 LTI 设计,再用 TDPA 做运行时安全保证,是最合理的组合。
7.4 开放问题¶
| 问题 | 当前状态 | 挑战 |
|---|---|---|
| 非线性稳定分析 | Llewellyn 是 LTI 工具 | RL 策略在环是高度非线性的 |
| 深空遥操作 | >1s 延迟下 bilateral 失效 | Supervisory 的人因效率差 |
| 共享自主 | 人机意图融合 | 缺乏统一数学框架 |
| 多模态触觉 | 温度/纹理/振动传输 | 通道带宽和心理物理学模型不足 |
| 变拓扑接触 | 抓取/释放的拓扑变化 | 离散事件+连续控制的混合 |
| 学习型遥操作 | D04 的 ACT/RL + D05-D07 力反馈 | 力反馈如何与学习策略交互 |
本章小结¶
| 知识点 | 核心结论 | 难度 |
|---|---|---|
| 遥操作历史 | 机械联动→电控→理论化;Ferrell 1965 揭示延迟的摧毁性影响 | ⭐ |
| 二端口 h 参数 | 混合参数匹配遥操作因果结构(master 阻抗 + slave 导纳) | ⭐⭐ |
| 操作者感受阻抗 | \(Z_{to} = h_{11} - h_{12}h_{21}Z_e/(1+h_{22}Z_e)\) | ⭐⭐ |
| 理想透明度 | \(H_{ideal} = [0,1;-1,0]\):系统"消失" | ⭐⭐ |
| Llewellyn 准则 | 四条充要条件;\(\eta(\omega) \geq 0\) 是核心 | ⭐⭐⭐ |
| 透明度-稳定性 trade-off | \(\eta = 0\) 恰好在稳定边界;加阻尼→\(\eta > 0\) 但透明度降 | ⭐⭐⭐ |
| 时延影响 | 延迟降低 \(\eta\) 变负的临界频率,使操作频段内不稳定 | ⭐⭐⭐ |
| 四种子架构 | PP(无力传感)/PF(slave力传感)/FP(少用)/FF(理论最优) | ⭐⭐ |
| Z-width | \(K_{max} = 2b/T\);采样率翻倍→Z-width 翻倍 | ⭐⭐ |
累积项目:本章新增模块¶
Mini-DualArm 项目进度:
| 章节 | 新增模块 | 功能 |
|---|---|---|
| D01-D04 | 双臂协调+学习管线 | 任务分类→规划→力控→ACT/RL 训练 |
| D05 | 二端口分析工具 | 给定控制器→计算 h 矩阵→绘制 \(\eta(\omega)\)→判断稳定性 |
| D05 | Z-width 计算器 | 给定 \(b, T\)→计算 \(K_{max}\)→判断力反馈可行性 |
延伸阅读¶
| 资源 | 类型 | 难度 | 关注点 |
|---|---|---|---|
| Hannaford 1989, "A Design Framework for Teleoperators with Kinesthetic Feedback" | 论文 | ⭐⭐⭐ | h 参数+四种架构——遥操作建模必读 |
| Lawrence 1993, "Stability and Transparency in Bilateral Teleoperation" | 论文 | ⭐⭐⭐⭐ | 透明度严格定义+Llewellyn——理论基石 |
| Colgate-Brown 1994, "Factors Affecting the Z-Width of a Haptic Display" | 论文 | ⭐⭐⭐ | Z-width 理论+虚拟墙被动条件 |
| Hokayem-Spong 2006, "Bilateral Teleoperation: An Historical Survey" | 综述 | ⭐⭐ | 领域历史地图——适合课前全景阅读 |
| Hashtrudi-Zaad-Salcudean 2001, "Analysis of Control Architectures for Teleoperation" | 论文 | ⭐⭐⭐ | I/A 组合选型原则 |
| Yokokohji-Yoshikawa 1994, "Bilateral Control for Ideal Kinesthetic Coupling" | 论文 | ⭐⭐⭐⭐ | 理想运动觉耦合三条件 |
| Ferrell 1965, "Remote Manipulation with Transmission Delay" | 论文 | ⭐⭐ | 经典延迟实验——理解"为什么延迟是问题" |
| Hirche-Buss 2012, "Human-Oriented Control for Haptic Teleoperation" | 书 | ⭐⭐⭐ | Model-Mediated + 共享控制综合参考 |
| Llewellyn 1952, "Some Fundamental Properties of Transmission Systems" | 论文 | ⭐⭐⭐⭐ | 原始论文——微波电路稳定性理论 |
| Zames 1966, "On the Input-Output Stability of Time-Varying Feedback Systems" | 论文 | ⭐⭐⭐⭐ | 小增益定理——超越 Llewellyn 的非线性工具 |
| Goertz 1952, "Fundamentals of General Purpose Remote Manipulators" | 论文 | ⭐ | 历史起源——遥操作领域的 Genesis Paper |
故障排查手册¶
| 症状 | 可能原因 | 排查步骤 | 相关章节 |
|---|---|---|---|
| 接触硬墙时系统振荡 | \(K > K_{max}\)(被动性违反) | 1. 测量实际采样频率 2. 计算 \(K_{max}=2b/T\) 3. 降低 \(K\) 或提高频率 | 本章 5.2 |
| 自由空间中 master 有"粘滞感" | \(h_{11}\) 实部过大 | 1. 降低本地阻尼 2. 检查齿轮摩擦 3. 加摩擦补偿 | 本章 2.2 |
| 力反馈强度随频率变化 | \(h_{12}\) 频率特性不平坦 | 1. 绘制 \(h_{12}\) Bode 图 2. 检查力传感器带宽 3. 加补偿滤波器 | 本章 4.3 |
| 延迟增加后系统不稳定 | Llewellyn \(\eta < 0\) | 1. 增加本地阻尼 2. 降低环路增益 3. 考虑波变量(D06)/TDPA(D07) | 本章 3.5 |
| Master 和 slave 位置漂移 | 积分器无保护 | 1. 检查位置重置机制 2. 加弱弹簧归中力 3. 检查积分抗饱和 | 本章 4.2 |
| \(\eta\) 在特定频率突然变负 | 控制器谐振+时延 | 1. 绘制 \(\eta(\omega)\) 全频段 2. 找到最小 \(\eta\) 频率 3. 加陷波滤波器 | 本章 3.5 |
| Z-width 不足以渲染目标环境 | 采样率太低或物理阻尼太小 | 1. 提高采样频率(最有效) 2. 增加虚拟阻尼 3. 降低目标刚度 | 本章 5.2 |
| h 参数计算结果与仿真不符 | 线性化误差或符号错误 | 1. 检查被动符号约定(流入为正) 2. 验证频率范围 3. 对比数值/解析 | 本章 2.2 |
D05 到 D06 承接:本章建立了分析框架并揭示了"透明度 vs 稳定性"的根本矛盾——延迟使 Llewellyn \(\eta\) 降低,需增大阻尼。有没有不牺牲透明度就能保持稳定性的方法? D06 将给出答案——散射变换和波变量理论,通过改变信号表示使通信通道在任意延迟下保持无源。
D05 到 D07 承接:Llewellyn 准则是 LTI 分析工具——它告诉你"名义上是否稳定"。但实际系统存在非线性、时变效应。D07 的 TDPA 提供了运行时安全保证——即使 Llewellyn 分析遗漏了某些因素,TDPA 也能在线检测并纠正。