跳转至

本文档属于 Robotics Tutorial 项目,作者:Pengfei Guo,达妙科技。采用 CC BY 4.0 协议,转载请注明出处。

F09 学习型力控——数据驱动的柔顺操作

本章定位:本章从经典力控(F01-F08)跨入学习型力控——用数据驱动方法解决经典方法难以处理的问题:未知环境参数、复杂接触几何、高维操作策略。核心思路不是"用学习替代控制",而是"学习与控制共生":学习提供高层决策(在什么位姿用什么刚度),控制提供结构化、可限幅的底层执行;接触稳定和真机安全仍要承接 F06 的无源性/能量罐/KB 条件/力矩限幅安全层。本章覆盖 VICES(阻抗参数作为 RL 动作空间)、SERL(25 分钟学会 PCB 插入)、Diffusion Policy + 底层阻抗、FALCON(人形力课程 RL)四大范式,以及 sim-to-real 在力控中的独特挑战。

前置依赖:F04(笛卡尔阻抗工程/libfranka)、F06(变阻抗无源性与安全层)、F01(力控导论/控制频率层级)、RL 基础(PPO/SAC,可参考 v8 Ch36 或自学)

下游章节:F10(综合实战)

建议用时:3 周(经典到学习的过渡 0.5 周 + VICES/SERL 1 周 + Diffusion/FALCON 1 周 + 实验 0.5 周)


前置自测 ⭐

📋 答不出 >= 2 题 → 先回前置章节复习

编号 问题 答不出时回顾
1 若本章采用 \(e_x=x_d-x\),笛卡尔阻抗控制律 \(\tau = J^T(K_d e_x - D_d \dot{x}) + g(q)\) 中,\(K_d\)\(D_d\) 的物理含义是什么?它们如何影响接触行为? F03/F04
2 策略频率(10-30 Hz)和控制频率(500-1000 Hz)为什么要分开?如果策略直接以 1kHz 输出力矩会怎样? F01 第 4 节
3 SAC(Soft Actor-Critic)的核心思想是什么?它与 PPO 的主要区别是什么? RL 基础
4 什么是 sim-to-real gap?力控任务中 sim-to-real 的主要挑战是什么? P02
5 F07 的 WBC-QP 中,阻抗参数 \(K_p, K_d\) 出现在什么位置(代价函数还是约束)? F07 第 3 节

本章目标

学完本章后,你应该能够:

  1. **解释**为什么需要学习型力控——经典方法在什么场景下"不够用"
  2. 理解 VICES 的核心思想:阻抗参数作为 RL 动作空间,以及为什么这比直接输出力矩更好
  3. 掌握 SERL 的完整管线:RLPD 算法 + serl_franka_controllers + agentlace 异步通信
  4. 理解 Diffusion Policy + 底层阻抗的架构:学习不替代控制,而是与控制共生
  5. 理解 FALCON 的力课程:从 0 N 外力渐增到 ~100 N(约 10 kgf)的渐进式训练策略
  6. 分析 sim-to-real 在力控中的独特挑战,并知道主要的应对方案

F9.1 从经典到学习——为什么需要学习型力控 ⭐

动机——经典力控的三个天花板

回顾 F01-F08:我们已经掌握了从阻抗控制到 WBC 到 MPC+WBC 的完整经典力控栈。这些方法在结构化环境(已知几何、已知接触参数)中表现优秀。但以下三个场景暴露了经典方法的根本局限。

天花板 1:未知环境参数

经典阻抗控制需要什么:
  - 环境刚度 K_e(用于选择阻抗参数)
  - 摩擦系数 mu(用于摩擦锥约束)
  - 接触几何(用于选择力控方向)

现实中这些参数通常未知:
  - 不同材质的 K_e 差 1000 倍(海绵 vs 钢铁)
  - mu 随表面状态变化(干 vs 湿 vs 油污)
  - 复杂零件的接触几何无法预先建模

经典方法的应对: 保守设计——用最刚硬的环境参数设计阻抗
  代价: 在柔软环境中动作过于缓慢,效率极低

天花板 2:高维操作策略

经典方法的参数数量:
  阻抗控制: K_d(6) + D_d(6) = 12 个参数
  力位混合: S(6) + K_p(6) + K_d(6) + K_fp(6) + K_fi(6) = 30 个参数

人类调参能力: ~10-20 个参数(靠直觉和试错)

复杂操作任务的参数需求:
  多阶段装配: 每个阶段不同的 K_d, D_d -> 阶段数 x 12 参数
  接触丰富任务: K_d 需要随状态连续变化 -> 无穷维策略

-> 人类无法手动设计高维操作策略
-> 需要数据驱动方法自动学习

天花板 3:接触建模的不完美

力仿真的根本问题:
  - 接触力计算依赖接触模型(Hertz/Hunt-Crossley/...)
  - 所有接触模型都是近似——真实接触是多尺度弹塑性过程
  - 仿真中的接触刚度、阻尼、摩擦参数 != 真实值

经典方法的假设: 动力学模型精确
-> 模型误差直接变成力控误差

学习型方法的优势: 直接从真实数据学习
-> 不依赖精确模型(model-free RL)
-> 或从仿真学习后在真实中微调(sim-to-real + fine-tuning)

本质洞察:经典力控的核心假设是"世界是可建模的"——给定精确的模型参数,控制律可以解析求解。学习型力控的核心假设是"世界是可从数据中学习的"——不需要精确模型,从交互数据中直接学习策略。两者不是替代关系,而是互补关系:经典方法提供结构、可审计约束和安全层,学习方法提供适应性和泛化能力

学习型力控的分类

方法 学习什么 底层控制 代表工作
模仿学习+阻抗 运动轨迹 固定阻抗跟踪 DMP-force, ProMP+impedance
变阻抗 RL 阻抗参数 \([K_d, D_d, x_d]\) 阻抗控制器 VICES (2019)
残差 RL 残差力矩 \(\Delta\tau\) 基础控制器+残差 Johannink (2019)
端到端 RL+底层阻抗 末端位姿序列 底层 1kHz 阻抗 SERL (2024), Diffusion Policy
双智能体 RL locomotion+manipulation 分别训练 FALCON (2025)

跨领域类比:学习型力控就像"自动驾驶与传统汽车的关系"——你不是把发动机和变速箱都换成神经网络,而是在传统汽车(阻抗控制器 = 发动机+变速箱)的基础上加一个自动驾驶系统(RL 策略 = 感知+决策),让它自动决定油门和方向盘角度(阻抗参数)。但安全不是因为"用了阻抗就天然安全",而是因为底层还有限幅、制动、能量监控等独立安全层。

⚠️ 常见陷阱

💡 概念误区:认为学习型力控 = 端到端力矩输出
   新手想法:"RL 直接输出关节力矩,不需要阻抗控制了"
   实际上:直接力矩输出在接触任务中极其不稳定:
          - RL 策略频率 10-30 Hz,力矩更新间隔 30-100ms
          - 接触力在 1ms 内就能从 0 变到 100N
          - 30ms 的控制延迟 -> 力冲击 -> 零件损坏/传感器过载
          几乎所有成功的学习型力控都使用底层阻抗/导纳控制器。
   正确认识:学习 = 高层决策(策略频率);控制 = 底层执行(控制频率)。
🧠 思维陷阱:认为学习型方法不需要理解经典力控
   新手想法:"反正 RL 会自己学,我不需要理解阻抗控制"
   实际上:不理解阻抗控制就无法:
          - 设计合理的动作空间(VICES 需要知道 K_d 的物理含义)
          - 调底层控制器参数(SERL 的 serl_franka_controllers)
          - 设计奖励函数(力跟踪误差需要知道什么量级是"好")
          - 调试 sim-to-real 问题(哪些是控制问题,哪些是学习问题)
   正确认识:F01-F08 是 F09 的必要前置。

DMP-force 完整公式与代码 ⭐⭐

在进入 RL-based 方法之前,先掌握经典的**模仿学习+力控**方法。Dynamic Movement Primitives (DMP) 最初由 Ijspeert et al. (2002) 提出用于运动生成,后被 Pastor et al. (2009) 扩展为力控版本(DMP-force)。

为什么需要 DMP-force:标准 DMP 只编码位置轨迹 \(y(t)\)。但在力控任务中(如擦桌子、打磨),我们需要同时编码**期望位置轨迹**和**期望力曲线**。DMP-force 用两个耦合的 DMP 分别编码位置和力。

DMP-force 公式

位置 DMP(回顾):

\[\tau^2 \ddot{y} = \alpha_y(\beta_y(g - y) - \tau\dot{y}) + f_{pos}(s)$$ $$\tau \dot{s} = -\alpha_s s\]

其中 \(s\) 是相位变量(从 1 衰减到 0),\(g\) 是目标位置,\(f_{pos}(s) = \frac{\sum_i w_i \psi_i(s) s}{\sum_i \psi_i(s)}\) 是由高斯基函数加权的非线性强迫项。

力参考 DMP(新增;本节代码采用一阶残差模型):

\[\tau \dot{f}_d = \alpha_f\beta_f(f_g - f_d) + f_{force}(s)\]

其中 \(f_d\) 是期望力,\(f_g\) 是力目标(稳态力),\(f_{force}(s)\) 学习示教力曲线相对一阶收敛项的 residual/forcing term。这里不维护"力速度"状态,因此不要写包含 \(-\dot{f}_d\) 的二阶力动力学;示教时学习目标为 \(f_{force}^{target}=\tau\dot{f}_{demo}-\alpha_f\beta_f(f_g-f_{demo})\),与下面代码一致。

耦合机制:位置 DMP 的目标 \(g\) 可以被力反馈修正——当实际力偏离期望力时,沿力方向调整目标位置:

\[g_{corrected} = g + K_{coupling}(f_d - f_{measured}), \quad K_{coupling}\,[m/N]\]
"""
DMP-force 完整实现: 从示教到力控轨迹回放
"""
import numpy as np

class DMPForce:
    """位置+力耦合 DMP"""

    def __init__(self, n_basis=25, dt=0.001):
        self.n_basis = n_basis
        self.dt = dt
        self.alpha_y = 25.0
        self.beta_y = self.alpha_y / 4.0  # 临界阻尼
        self.alpha_f = 15.0
        self.beta_f = self.alpha_f / 4.0
        self.alpha_s = 1.0
        self.tau = 1.0  # 时间缩放

        # 高斯基函数中心和宽度
        self.c = np.exp(-self.alpha_s * np.linspace(0, 1, n_basis))
        self.h = 1.0 / (np.diff(self.c) ** 2)
        self.h = np.append(self.h, self.h[-1])

        # 权重(由 LWR 学习)
        self.w_pos = np.zeros((3, n_basis))  # 3D 位置
        self.w_force = np.zeros((3, n_basis))  # 3D 力

    def _basis(self, s):
        """计算高斯基函数值"""
        psi = np.exp(-self.h * (s - self.c) ** 2)
        return psi / (psi.sum() + 1e-10)

    def learn_from_demo(self, pos_demo, force_demo, dt_demo):
        """
        从示教轨迹学习 DMP 权重

        参数:
            pos_demo: (T, 3) 位置轨迹
            force_demo: (T, 3) 力轨迹
            dt_demo: 示教采样间隔
        """
        T = len(pos_demo)
        self.tau = T * dt_demo
        self.y0 = pos_demo[0].copy()
        self.g = pos_demo[-1].copy()
        self.f0 = force_demo[0].copy()
        self.fg = force_demo[-1].copy()

        # 计算相位轨迹
        s_demo = np.exp(-self.alpha_s * np.linspace(0, 1, T))

        # 对每个维度, 用 LWR 学习权重
        for d in range(3):
            # 位置: 计算强迫项目标值
            y = pos_demo[:, d]
            yd = np.gradient(y, dt_demo)
            ydd = np.gradient(yd, dt_demo)
            f_target_pos = (self.tau**2 * ydd
                           - self.alpha_y * (self.beta_y * (self.g[d] - y)
                                            - self.tau * yd))

            # LWR: w = (Phi^T W Phi)^{-1} Phi^T W f_target
            for i in range(self.n_basis):
                psi_i = np.exp(-self.h[i] * (s_demo - self.c[i])**2)
                self.w_pos[d, i] = (
                    np.sum(psi_i * s_demo * f_target_pos) /
                    (np.sum(psi_i * s_demo**2) + 1e-10)
                )

            # 力: 同样方法
            f = force_demo[:, d]
            fd = np.gradient(f, dt_demo)
            f_target_force = (self.tau * fd
                             - self.alpha_f * (self.beta_f * (self.fg[d] - f)))

            for i in range(self.n_basis):
                psi_i = np.exp(-self.h[i] * (s_demo - self.c[i])**2)
                self.w_force[d, i] = (
                    np.sum(psi_i * s_demo * f_target_force) /
                    (np.sum(psi_i * s_demo**2) + 1e-10)
                )

    def rollout(self, f_measured_fn, K_coupling=0.001):
        """
        执行 DMP 并返回位置和力参考轨迹

        参数:
            f_measured_fn: callable, 返回当前测量力 (3,)
            K_coupling: 力-位置耦合增益
        """
        y = self.y0.copy()
        yd = np.zeros(3)
        fd = self.f0.copy()
        s = 1.0

        trajectory = {'pos': [], 'vel': [], 'force_ref': []}

        steps = int(self.tau / self.dt)
        for t in range(steps):
            psi = self._basis(s)

            # 力反馈先修正目标位置,K_coupling 单位为 m/N。
            # 不要把位置修正量直接加到速度上;那会把 m 当成 m/s 使用。
            f_meas = f_measured_fn()
            force_error = fd - f_meas
            g_eff = self.g + K_coupling * force_error

            # 位置 DMP
            f_pos = self.w_pos @ (psi * s)
            ydd = (self.alpha_y * (self.beta_y * (g_eff - y) - self.tau * yd)
                   + f_pos) / self.tau**2

            # 力 DMP
            f_force = self.w_force @ (psi * s)
            fd_dot = (self.alpha_f * (self.beta_f * (self.fg - fd))
                      + f_force) / self.tau

            # 积分
            yd += ydd * self.dt
            y += yd * self.dt
            fd += fd_dot * self.dt
            s += (-self.alpha_s * s / self.tau) * self.dt

            trajectory['pos'].append(y.copy())
            trajectory['vel'].append(yd.copy())
            trajectory['force_ref'].append(fd.copy())

        return {k: np.array(v) for k, v in trajectory.items()}

DMP-force 的局限——引出 RL 方法的动机:

局限 说明 RL 如何解决
固定耦合增益 \(K_{coupling}\) 需手动调,不同阶段需要不同值 RL 自动学习时变增益
线性力修正 \(y_{correction} = K \cdot e_f\) 只能线性修正 RL 可以学习非线性修正策略
单次示教 一条轨迹只能覆盖一种情况 RL 从大量交互中学习鲁棒策略
无法处理接触模式切换 DMP 假设连续运动 RL 可以学习离散切换

ProMP + 阻抗参数联合学习 ⭐⭐

ProMP (Probabilistic Movement Primitives, Paraschos et al. 2013) 比 DMP 更强大——它编码轨迹的**概率分布**而非单条轨迹。ProMP+阻抗的思路:同时编码位置轨迹和阻抗参数轨迹的联合分布。

核心思想:将 \([\text{位置}(t), K_d(t), D_d(t)]\) 视为一个高维轨迹,用 ProMP 编码其联合分布。从多条示教中学习后,可以条件化(conditioning)到新的目标位姿,自动调整阻抗参数。

\[p(\tau_{pos}, \tau_{K}, \tau_{D}) = \mathcal{N}\left(\begin{bmatrix} \mu_{pos} \\ \mu_K \\ \mu_D \end{bmatrix}, \begin{bmatrix} \Sigma_{pp} & \Sigma_{pK} & \Sigma_{pD} \\ \Sigma_{Kp} & \Sigma_{KK} & \Sigma_{KD} \\ \Sigma_{Dp} & \Sigma_{DK} & \Sigma_{DD} \end{bmatrix}\right)\]

条件化到新目标 \(p_{goal}^{new}\) 时,阻抗参数自动调整:

\[p(K_d | p_{goal}^{new}) = \mathcal{N}(\mu_K + \Sigma_{Kp}\Sigma_{pp}^{-1}(p_{goal}^{new} - \mu_{pos}), \quad \Sigma_{KK} - \Sigma_{Kp}\Sigma_{pp}^{-1}\Sigma_{pK})\]

本质洞察:ProMP+阻抗的关键价值不是学习单条轨迹(DMP 已经能做),而是学习**位置和阻抗之间的统计关联**。例如,如果示教中总是在接近物体时降低 \(K_d\),ProMP 会学到"靠近物体 = 低刚度"的关联,自动在新目标附近降低刚度。

练习

  1. 场景分类:对以下场景判断经典力控是否足够:(a) Franka 以 5N 恒力打磨铝板,(b) Franka 在未知柔软物体上打磨,(c) 人形机器人用手开不同形状的瓶盖。
  2. 动作空间对比:列出关节力矩、关节位置增量、VICES 阻抗参数三种动作空间的维度和物理含义。哪种在接触任务中最安全?
  3. ⭐⭐ 边界分析:在什么条件下学习型方法会退化为经典方法?
  4. ⭐⭐ DMP-force 实现:用上述代码,从一条正弦力曲线示教中学习 DMP-force 权重。修改 \(K_{coupling}\) 从 0 到 0.01,观察力跟踪精度变化。

F9.2 VICES——阻抗参数作为 RL 动作空间 ⭐⭐

动机——为什么不直接输出力矩

回顾 F03:阻抗控制律 \(\tau = J^T(-K_d \tilde{x} - D_d \dot{\tilde{x}}) + g(q)\) 中,\(\tilde{x} = x - x_d\) 是误差(当前位姿减期望位姿),\((K_d, D_d, x_d)\) 是设计参数。为方便学习策略输出目标位姿,本节等价改写为 \(e_x = x_d - x\)(期望减当前),因此笛卡尔阻抗力写作 \(F = K_d e_x - D_d \dot{x}\),力矩为 \(\tau = J^T F + g(q)\)。VICES 的核心思想:让 RL 策略输出这些参数

VICES 架构(Martin-Martin et al. IROS 2019)

传统 RL 动作空间:
  a = tau (关节力矩) 或 a = Delta_q (关节位置偏移)
  问题: 接触不稳定;样本效率低

VICES:
  观测: o = [x_ee, F_ext, q, dq]
  动作: a = [K_d(6), D_d(6), x_d(6)]  属于 R^18
  底层: e_x = x_d - x
        tau = J^T(K_d*e_x - D_d * x_dot) + g(q)
  # 注意: 本节误差定义为 x_d - x(期望减当前),弹簧项为 +K_d*e_x

  关键: RL 策略不直接产生力矩
        而是选择"在什么位姿(x_d)用什么刚度(K_d)和阻尼(D_d)"
        底层阻抗控制器提供连续、可限幅的力矩生成;接触稳定还需 F06 安全层

为什么 VICES 比直接力矩输出更好?

对比项 力矩动作空间 VICES 阻抗动作空间
接触稳定性 不保证(力矩跳变->力冲击) 更容易约束;仍需无源性/限幅安全层
样本效率 低(需学大量接触物理) 高 3x+(阻抗编码了接触先验)
安全性 低(策略错误->高力矩->损坏) 高(K_d 有限->力有限)
策略频率 需要高频(>100Hz) 低频即可(10-30Hz)
动作含义 无物理直觉 有物理直觉(刚度=多硬)

类比:力矩动作空间就像让新手直接控制汽车每个轮子的扭矩——极其危险且低效。VICES 阻抗动作空间就像让新手控制方向盘和油门——底盘系统(阻抗控制器)把高层命令转化为更平滑的轮子扭矩,但仍需要限速、刹车和稳定控制这类独立安全机制。

奖励函数设计

r = r_task - w_K ||K_d|| - w_Da ||a - a_prev||
    |            |              |
    任务完成    能耗正则化    动作平滑
    (稀疏/稠密)  (防止K过大)  (防止抖动)

r_task 设计(peg-in-hole 为例):
  Phase 1 (搜索): r = -||p_peg_xy - p_hole_xy||
  Phase 2 (插入): r = -|z_peg - z_target|
  Phase 3 (完成): r = +100

代码框架

# VICES 环境(基于 stable-baselines3/PPO)
import gymnasium as gym
import numpy as np

class VICESEnv(gym.Env):
    def __init__(self, robot_env):
        self.robot = robot_env

        # 观测: x_ee(6) + F_ext(6) + q(7) + dq(7) = 26D
        self.observation_space = gym.spaces.Box(
            low=-np.inf, high=np.inf, shape=(26,)
        )

        # 动作: [K_d(6), D_d(6), x_d(6)] = 18D
        self.action_space = gym.spaces.Box(
            low=np.array([10]*6 + [1]*6 + [-0.1]*6),
            high=np.array([1000]*6 + [100]*6 + [0.1]*6),
        )

        self.control_freq = 1000  # 1 kHz
        self.policy_freq = 20     # 20 Hz
        self.substeps = self.control_freq // self.policy_freq

    def step(self, action):
        K_d = np.diag(action[0:6])
        D_d = np.diag(action[6:12])
        dx_d = action[12:18]
        x_d = self.current_x + dx_d

        # F06 安全层:策略输出先过参数限幅/速率限幅/能量罐或 KB 检查。
        # 变阻抗 RL 不能假设 K_d、D_d 任意跳变仍保持接触稳定。
        K_d, D_d, x_d = self.safety_filter(K_d, D_d, x_d)

        # 底层阻抗控制器执行 50 步(50ms)
        for _ in range(self.substeps):
            x_current = self.robot.get_ee_pose()
            x_dot = self.robot.get_ee_velocity()
            e_x = x_d - x_current
            F_cmd = K_d @ e_x - D_d @ x_dot
            tau = self.robot.J.T @ F_cmd + self.robot.gravity()
            self.robot.step(tau)

        obs = self._get_obs()
        reward = self._compute_reward()
        done = self._check_done()
        return obs, reward, done, False, {}

    def safety_filter(self, K_d, D_d, x_d):
        # 教学骨架:工程中在这里接 F06 的 KB 下界、energy tank、
        # K_dot 限幅、x_d 速率限幅和力矩限幅。
        return K_d, D_d, x_d

RL 变阻抗策略——SAC + impedance action space 完整设置 ⭐⭐⭐

VICES 使用 PPO 作为 RL 算法。但在连续动作空间中,SAC (Soft Actor-Critic) 通常更高效——它通过最大化策略熵来鼓励探索,对阻抗参数这种连续且多模态的动作空间特别合适。

为什么 SAC 比 PPO 更适合变阻抗学习

特性 PPO SAC
数据效率 低(on-policy,用过即弃) 高(off-policy,replay buffer)
探索策略 高斯噪声(各向同性) 最大熵(自适应方向性探索)
对阻抗空间的意义 各方向均匀探索 K_d 优先探索不确定方向的 K_d
真机训练可行性 差(需要大量数据) 好(UTD 高,数据复用)

完整 SAC + impedance 训练设置

"""
SAC + 变阻抗动作空间: peg-in-hole 完整训练脚本
基于 stable-baselines3 + gymnasium
"""
import gymnasium as gym
import numpy as np
import torch
from stable_baselines3 import SAC
from stable_baselines3.common.callbacks import EvalCallback
from stable_baselines3.common.noise import NormalActionNoise

# === Step 1: 定义变阻抗环境 ===
class VariableImpedanceEnv(gym.Env):
    """
    动作空间: [K_d(6), delta_x_d(6)] = 12D
    (D_d 由临界阻尼自动计算: D = 2*sqrt(K*m_eff))
    观测空间: [x_ee(6), F_ext(6), q(7), dq(7), phase(1)] = 27D
    """

    def __init__(self, sim_env, max_episode_steps=500):
        super().__init__()
        self.sim = sim_env
        self.max_steps = max_episode_steps

        # 动作空间: 归一化到 [-1, 1]
        self.action_space = gym.spaces.Box(
            low=-1.0, high=1.0, shape=(12,), dtype=np.float32
        )

        # 观测空间
        self.observation_space = gym.spaces.Box(
            low=-np.inf, high=np.inf, shape=(27,), dtype=np.float32
        )

        # 阻抗参数范围 (物理单位)
        self.K_min = np.array([20, 20, 10, 2, 2, 2])      # N/m, Nm/rad
        self.K_max = np.array([600, 600, 400, 40, 40, 40])
        self.dx_max = np.array([0.01, 0.01, 0.01, 0.05, 0.05, 0.05])  # m, rad

        # 有效质量 (近似)
        self.m_eff = np.array([3.0, 3.0, 3.0, 0.5, 0.5, 0.5])

        # 控制频率
        self.ctrl_freq = 1000  # 底层阻抗 1kHz
        self.policy_freq = 20   # 策略 20Hz
        self.substeps = self.ctrl_freq // self.policy_freq

        self.step_count = 0
        self.prev_action = np.zeros(self.action_space.shape, dtype=np.float32)

    def _scale_action(self, action):
        """将 [-1,1] 动作映射到物理单位"""
        K_normalized = action[:6]
        dx_normalized = action[6:12]

        K_d = self.K_min + (K_normalized + 1) / 2 * (self.K_max - self.K_min)
        dx_d = dx_normalized * self.dx_max

        # 自动临界阻尼
        D_d = 2.0 * np.sqrt(K_d * self.m_eff)

        # F06 安全层入口:限制 K 变化率,并用 KB 下界或能量罐裁剪不安全升刚度。
        K_d, D_d = self.passivity_filter(K_d, D_d)

        return K_d, D_d, dx_d

    def passivity_filter(self, K_d, D_d):
        # 教学骨架:根据上一周期 K_d 计算 K_dot,
        # 用 F06 的 KB 条件或 energy tank 缩放不安全的升刚度。
        return K_d, D_d

    def step(self, action):
        K_d, D_d, dx_d = self._scale_action(action)
        x_d = self.sim.get_ee_pose() + dx_d

        # 底层阻抗控制器执行 50 步 (50ms)
        total_force = np.zeros(6)
        for _ in range(self.substeps):
            x = self.sim.get_ee_pose()
            x_dot = self.sim.get_ee_velocity()

            e_x = x_d - x
            F_cmd = K_d * e_x - D_d * x_dot
            tau = self.sim.J.T @ F_cmd + self.sim.gravity()

            # 力矩安全裁剪
            tau_max = np.array([87, 87, 87, 87, 12, 12, 12], dtype=float)
            tau = np.clip(tau, -tau_max, tau_max)
            self.sim.step(tau)

            total_force += self.sim.get_ee_force()

        avg_force = total_force / self.substeps
        self.step_count += 1

        obs = self._get_obs()
        reward = self._compute_reward(avg_force, K_d, action)
        terminated = self._check_success()
        truncated = self.step_count >= self.max_steps

        return obs, reward, terminated, truncated, {
            'K_d': K_d, 'force': avg_force, 'success': terminated
        }

    def _compute_reward(self, force, K_d, action):
        """
        多分量奖励函数设计 (peg-in-hole)
        """
        peg_pos = self.sim.get_peg_position()
        hole_pos = self.sim.get_hole_position()

        # 1. 距离奖励 (稠密)
        xy_dist = np.linalg.norm(peg_pos[:2] - hole_pos[:2])
        z_progress = max(0, hole_pos[2] - peg_pos[2])  # 插入深度
        r_distance = -2.0 * xy_dist + 5.0 * z_progress

        # 2. 力安全奖励 (惩罚过大侧向力)
        lateral_force = np.linalg.norm(force[:2])
        r_force = -0.1 * max(0, lateral_force - 10.0)  # 超过 10N 惩罚

        # 3. 阻抗正则化 (鼓励合理 K_d)
        r_impedance = -0.001 * np.sum(K_d)  # 轻微鼓励低刚度

        # 4. 动作平滑 (惩罚突变)
        r_smooth = -0.01 * np.sum(np.abs(action - self.prev_action))
        self.prev_action = action.copy()

        # 5. 成功奖励 (稀疏)
        r_success = 100.0 if self._check_success() else 0.0

        return r_distance + r_force + r_impedance + r_smooth + r_success

    def _get_obs(self):
        x_ee = self.sim.get_ee_pose()
        f_ext = self.sim.get_ee_force()
        q = self.sim.get_joint_positions()
        dq = self.sim.get_joint_velocities()
        phase = np.array([self.step_count / self.max_steps])
        return np.concatenate([x_ee, f_ext, q, dq, phase])

# === Step 2: SAC 训练 ===
env = VariableImpedanceEnv(sim_env=create_mujoco_peg_env())
eval_env = VariableImpedanceEnv(sim_env=create_mujoco_peg_env())

model = SAC(
    "MlpPolicy",
    env,
    learning_rate=3e-4,
    buffer_size=1_000_000,
    learning_starts=10_000,     # 先收集 10K 步
    batch_size=256,
    tau=0.005,                   # 软更新系数
    gamma=0.99,
    train_freq=1,                # 每步训练一次
    gradient_steps=1,            # 默认 UTD=1; 真机可设 20
    ent_coef='auto',             # 自动熵调节 (SAC 核心)
    policy_kwargs=dict(
        net_arch=[256, 256],     # 两层 MLP
        activation_fn=torch.nn.ReLU,
    ),
    verbose=1,
)

eval_callback = EvalCallback(
    eval_env,
    best_model_save_path="./best_model/",
    eval_freq=5000,
    n_eval_episodes=10,
)

model.learn(total_timesteps=500_000, callback=eval_callback)

理论到工程衔接:注意 ent_coef='auto' —— 这是 SAC 的核心:自动调节探索程度。在训练初期,熵系数高,策略大胆探索不同的 \(K_d\) 组合;随着训练进行,熵系数自动降低,策略收敛到最优阻抗。这比 PPO 的固定高斯噪声探索更高效,因为 SAC 会**选择性地在不确定的方向上探索**(如 z 方向刚度),而非均匀地在所有方向加噪声。

残差策略学习完整框架 ⭐⭐

残差 RL(Johannink et al. 2019, Silver et al. 2018)是 VICES 的简化变体,但有其独特优势。不学习完整的阻抗参数,只学习一个"残差修正" 叠加在手工基础控制器上。

残差策略学习的三种变体

变体 A — 残差力矩 (Johannink 2019):
  基础控制器: e_x = x_d - x
              tau_base = J^T(K_d*e_x - D_d * x_dot) + g
  残差策略:   Delta_tau = pi_theta(o)       属于 R^7 (关节力矩)
  最终力矩:   tau = tau_base + clip(Delta_tau, -tau_max_residual, tau_max_residual)
  安全: tau_max_residual = 10 Nm (约为额定力矩的 10-15%)

变体 B — 残差位姿 (Silver 2018):
  基础控制器: x_d_base = trajectory_planner(t)
  残差策略:   Delta_x = pi_theta(o)         属于 R^6 (位姿增量)
  最终参考:   x_d = x_d_base + clip(Delta_x, -dx_max, dx_max)
  底层阻抗:   e_x = x_d - x
              tau = J^T(K_d*e_x - D_d * x_dot) + g
  安全: dx_max = [5mm, 5mm, 5mm, 0.05rad, 0.05rad, 0.05rad]

变体 C — 残差力 (混合):
  基础控制器: e_x = x_d - x
              F_base = selection_matrix @ [K_d*e_x - D_d*x_dot; f_target]
  残差策略:   Delta_F = pi_theta(o)         属于 R^6 (力增量)
  最终力:     F = F_base + clip(Delta_F, -F_max_residual, F_max_residual)
  底层:       tau = J^T @ F + g
  安全: F_max_residual = [5N, 5N, 5N, 1Nm, 1Nm, 1Nm]
变体 动作维度 物理含义 安全性 适用场景
A 力矩残差 7D 关节力矩修正 精细力调整
B 位姿残差 6D 末端位姿修正 精度补偿
C 力残差 6D 笛卡尔力修正 力跟踪增强

反事实推理:如果残差 \(\Delta\tau\) 的范围不限制会怎样?\(\Delta\tau\) 可能完全覆盖 \(\tau_{base}\)(如 \(\Delta\tau = -\tau_{base} + \tau_{arbitrary}\)),退化为端到端力矩输出——失去底层阻抗带来的结构化约束。所以残差必须限幅。

残差幅度与基础控制器质量的关系

基础控制器很好 (如经过精心调参的阻抗控制):
  Delta_tau_max = 5% * tau_rated  -> RL 只做微调
  训练步数: 50K-100K (很快收敛)
  风险: 低

基础控制器一般 (如默认参数):
  Delta_tau_max = 20% * tau_rated -> RL 需要更多修正
  训练步数: 200K-500K
  风险: 中

基础控制器很差 (如无重力补偿):
  Delta_tau_max -> 需要很大 -> 接近端到端 -> 失去残差优势
  结论: 不应使用残差 RL, 应先修好基础控制器

本质洞察:残差策略学习的本质是**用学习能力填补基础控制器的"最后一英里"差距**。它不是替代基础控制器,而是增强基础控制器。基础控制器越好,残差越小,训练越快,系统越安全。如果基础控制器很差(需要大残差才能工作),残差 RL 就退化为端到端——此时应回到 F01-F08 先改进基础控制器。

⚠️ 常见陷阱

⚠️ 编程陷阱:VICES 动作空间的范围设置不当
   错误做法:K_d 范围 [0, 10000] N/m
   现象:RL 探索时 K_d = 10000 -> 末端像刚性位控 -> 接触力冲击
   根本原因:K_d 的物理上限应根据安全力设定
   正确做法:K_max = F_safe / dx_max
            如 F_safe = 50N, dx_max = 0.005m -> K_max = 10000
            但实际应更保守: K_max = 500-1000 N/m
💡 概念误区:认为 VICES 只适合 peg-in-hole
   新手想法:"VICES 论文只做了装配,可能不通用"
   实际上:VICES 的核心思想(阻抗参数作为动作空间)适用于所有力控操作。
          后续工作扩展到打磨(Bogdanovic 2020)、擦拭(Luo 2019)等。
          关键不是具体任务,而是"底层阻抗+高层学习"的架构模式。

练习

  1. 动作空间简化:如果固定 \(D_d = 2\sqrt{K_d \cdot m}\)(临界阻尼自动计算),动作空间从 18D 降为 12D。这种简化在什么情况下合理?什么情况下不行?
  2. ⭐⭐ VICES 复现:在 MuJoCo Franka + robosuite 中,用 PPO 训练 peg-in-hole:动作空间分别用 (a) joint torque 和 (b) VICES,对比 500K 步后成功率。
  3. ⭐⭐ 奖励工程:为"用 Franka 擦桌子"设计 VICES 奖励函数。需考虑法向力 5-10N、切向速度跟踪、覆盖率。

F9.3 SERL——25 分钟学会 PCB 插入 ⭐⭐

动机——从仿真到真机的飞跃

VICES 在仿真中表现优秀,但真机训练面临两个问题:(1) 样本效率不够高,(2) 需要手动重置。SERL(Luo et al. ICRA 2024)解决了这两个问题。

SERL 三进程架构

┌── Actor 进程 (GPU) ────────────┐
│  策略推理: obs -> action        │
│  频率: 20 Hz                   │
└──────────┬─────────────────────┘
           │ agentlace(异步网络通信)
┌── Learner 进程 (GPU) ──────────┐
│  RLPD 训练 (SAC 变体)          │
│  UTD = 20                      │
└──────────┬─────────────────────┘
           │ agentlace
┌── Environment 进程 (CPU) ──────┐
│  franka_env + serl_controllers │
│  1 kHz 阻抗控制               │
└──────────┬─────────────────────┘
        Franka Panda 真机

RLPD 关键技巧

改进 1: 对称采样
  原始: (s, a, s') -> 镜像: (flip(s), flip(a), flip(s'))
  效果: 利用对称性,数据量 2x

改进 2: LayerNorm
  在 critic 和 actor 网络中加 LayerNorm
  效果: 稳定训练

改进 3: 高 UTD = 20
  每收集 1 个数据点,做 20 次梯度更新
  效果: 极致利用每个真机数据

改进 4: 人类 Demo Warm-start
  20 个遥操作 demo 预填充 replay buffer
  效果: 从"合理行为"开始,非随机探索

底层控制器:serl_franka_controllers

class CartesianImpedanceController {
    // 固定阻抗参数
    Eigen::Matrix<double, 6, 1> K = {300, 300, 300, 30, 30, 30};

    // 误差裁剪(安全)
    double max_pos_error = 0.05;   // 5cm
    double max_ori_error = 0.3;    // 0.3 rad

    void update(const Eigen::Matrix<double, 6, 1>& x_desired) {
        Eigen::Matrix<double, 6, 1> error = x_desired - x_current;

        // 裁剪误差
        error.head<3>() = error.head<3>().cwiseMin(max_pos_error)
                                          .cwiseMax(-max_pos_error);
        error.tail<3>() = error.tail<3>().cwiseMin(max_ori_error)
                                          .cwiseMax(-max_ori_error);

        // error = x_desired - x_current(期望减当前)
        // 力矩 = J^T * (-K * (-error) - D * x_dot) = J^T * (K * error - D * x_dot)
        // 等价于 tau = J^T * (-K * (x - x_d) - D * x_dot) + g
        tau = J.transpose() * (K.asDiagonal() * error
                               - D.asDiagonal() * x_dot)
              + gravity;
    }
};

误差裁剪的关键作用:策略输出的 \(x_d\) 可能跳变(RL 探索),裁剪确保即使 \(x_d\) 跳到很远,阻抗误差也不超过设定范围。它是安全层的一部分,但不是无源性证明;真机部署仍应叠加 F06 的力矩限幅、速度限幅、能量监测和碰撞检测。

不是 X 而是 Y:SERL 的底层阻抗**不是**可学习的(\(K_d\) 固定),**而是**可审计的执行层。学习发生在策略网络(输出 \(\Delta x_d\)),不在控制器。这与 VICES 不同——VICES 学习 \(K_d\) 本身,因此更需要 F06 的变阻抗安全过滤。

SERL 结果

任务 训练时间 成功率 特点
PCB 插入 25 分钟 100% 0.5mm 精度
电缆布线 50 分钟 95% 柔性物体
齿轮装配 40 分钟 98% 多步操作

HIL-SERL(2024 扩展)

HIL-SERL = Human-in-the-Loop SERL:
  正常运行: RL 策略控制
  异常检测: 如果策略进入"坏状态"
  人类介入: 操作员遥操作接管,纠正到正常
  数据利用: 人类纠正数据加入 replay buffer
  效果: 更少 demo + 更快收敛 + 工业可部署

⚠️ 常见陷阱

⚠️ 编程陷阱:agentlace 网络延迟过高
   错误做法:Actor 和 Learner 在不同机器上,网络延迟 > 10ms
   现象:策略已更新但 Actor 还用旧策略,训练不稳定
   正确做法:同一台机器(同一 GPU),或高速局域网(延迟 < 1ms)
💡 概念误区:认为 SERL 的 20 个 demo 不重要
   新手想法:"25 分钟就能学会,demo 只是锦上添花"
   实际上:没有 demo,SERL 需要 2-4 小时(随机探索效率极低)。
          20 个 demo 把 replay buffer 初始化到"合理行为附近"。
   正确理解:demo 提供"搜索空间先验",不是"最终策略"。

练习

  1. UTD 分析:UTD=20,Franka 20 Hz 采集数据。每秒多少新数据?Learner 需多少梯度更新/秒?假设 1ms/步,GPU 利用率?
  2. ⭐⭐ SERL 仿真:用 SERL sim 模式训练 PCB 插入。修改 K 从 300 到 100,成功率变化?
  3. ⭐⭐ 误差裁剪实验:max_pos_error 从 5cm 改为 1cm 和 20cm 分别训练,分析探索/安全 trade-off。

F9.4 Diffusion Policy + 底层阻抗 ⭐⭐

动机——从行为克隆到扩散策略

Diffusion Policy(Chi et al. RSS 2023, ~1500 引用)用扩散模型生成机器人动作序列。

架构

观测 o_t -> 条件编码器 -> 条件向量 c
                          |
                          v
噪声 z ~ N(0,I) -> 去噪(K步) -> 未来 T 步动作 {a_t, ..., a_{t+T}}

动作含义:
  a_t = x_d(t)  末端目标位姿
  频率: 10 Hz
  轨迹长度: T = 8-16 步

底层控制器 (1 kHz):
  阻抗/导纳跟踪 x_d(t)
  K_d 适中(200-500 N/m)

关键理解:Diffusion Policy 输出**不是力矩**而是**末端位姿轨迹**。力控由底层阻抗实现。

不是 X 而是 Y:Diffusion Policy 的成功**不在于**替代了力控,**而在于**利用了底层阻抗的结构化执行和可限幅接口。没有阻抗底层,直接力矩输出在接触任务中几乎不可用;只有阻抗底层也不等于自动稳定,仍要保留 F06 的安全监控。

chi/diffusion_policy 代码——从数据到推理 ⭐⭐⭐

chi (Cheng et al.) 和 diffusion_policy (Chi et al.) 是两个主流 Diffusion Policy 开源实现。以下给出完整的训练和推理流程。

数据格式

"""
Diffusion Policy 训练数据格式 (基于 robomimic/HDF5)
"""
# 每条 demo 包含:
# obs/ee_pos:        (T, 3)   末端位置
# obs/ee_quat:       (T, 4)   末端四元数
# obs/joint_pos:     (T, 7)   关节位置
# obs/joint_vel:     (T, 7)   关节速度
# obs/force_torque:  (T, 6)   力/力矩传感器 <-- 力控关键
# obs/agentview_image: (T, 84, 84, 3)  相机图像 (可选)
# actions:           (T, 6)   末端位姿增量 [dx, dy, dz, drx, dry, drz]

训练脚本

"""
Diffusion Policy 力控任务训练 (基于 diffusion_policy 库)
"""
from diffusion_policy.workspace.train_diffusion_unet_workspace import (
    TrainDiffusionUnetWorkspace
)
import hydra
from omegaconf import OmegaConf

# 配置 (YAML 等效)
config = {
    'task': {
        'name': 'peg_insertion_force',
        'dataset': {
            'path': 'data/peg_insertion_demos.hdf5',
            'horizon': 16,          # 预测 16 步未来动作
            'n_obs_steps': 2,       # 用 2 步历史观测
            'n_action_steps': 8,    # 执行 8 步 (open-loop)
            'pad_before': 1,
            'pad_after': 7,
        },
        'shape_meta': {
            'obs': {
                'ee_pos':       {'shape': [3]},
                'ee_quat':      {'shape': [4]},
                'force_torque': {'shape': [6]},  # 力观测
                'joint_pos':    {'shape': [7]},
            },
            'action': {'shape': [6]},  # 末端位姿增量
        },
    },
    'policy': {
        'noise_scheduler': {
            'type': 'DDPMScheduler',
            'num_train_timesteps': 100,
            'beta_start': 0.0001,
            'beta_end': 0.02,
            'beta_schedule': 'squaredcos_cap_v2',
        },
        'unet': {
            'down_dims': [256, 512, 1024],
            'kernel_size': 5,
            'n_groups': 8,
            'diffusion_step_embed_dim': 128,
            'cond_predict_scale': True,
        },
        'obs_encoder': {
            'type': 'LowDimEncoder',
            'output_dim': 256,
        },
        'horizon': 16,
        'n_action_steps': 8,
        'n_obs_steps': 2,
        'num_inference_steps': 16,  # 推理时去噪步数 (训练100, 推理可减少)
    },
    'training': {
        'lr': 1e-4,
        'weight_decay': 1e-6,
        'batch_size': 64,
        'num_epochs': 500,
        'ema_decay': 0.995,         # EMA 模型平均 (稳定推理)
    },
}

# 训练
workspace = TrainDiffusionUnetWorkspace(OmegaConf.create(config))
workspace.run()

推理与底层阻抗对接

"""
Diffusion Policy 推理 + 底层笛卡尔阻抗控制
"""
import numpy as np
import torch

class DiffusionForceController:
    """Diffusion Policy + 1kHz 阻抗底层"""

    def __init__(self, policy_path, robot_interface):
        self.policy = load_diffusion_policy(policy_path)
        self.robot = robot_interface

        # 底层阻抗参数
        self.K_d = np.diag([300, 300, 300, 30, 30, 30])
        self.D_d = np.diag([40, 40, 40, 5, 5, 5])
        self.max_pos_error = 0.03   # 3cm 误差裁剪
        self.max_ori_error = 0.15   # 0.15 rad

        # 策略参数
        self.policy_freq = 10  # Hz
        self.ctrl_freq = 1000  # Hz
        self.action_horizon = 8
        self.obs_buffer = []

    @staticmethod
    def _quat_conj(q):
        return np.array([q[0], -q[1], -q[2], -q[3]])

    @staticmethod
    def _quat_mul(q1, q2):
        # quaternion order: [w, x, y, z]
        w1, x1, y1, z1 = q1
        w2, x2, y2, z2 = q2
        return np.array([
            w1*w2 - x1*x2 - y1*y2 - z1*z2,
            w1*x2 + x1*w2 + y1*z2 - z1*y2,
            w1*y2 - x1*z2 + y1*w2 + z1*x2,
            w1*z2 + x1*y2 - y1*x2 + z1*w2,
        ])

    @staticmethod
    def _rotvec_to_quat(rotvec):
        theta = np.linalg.norm(rotvec)
        if theta < 1e-9:
            return np.array([1.0, 0.5*rotvec[0], 0.5*rotvec[1], 0.5*rotvec[2]])
        axis = rotvec / theta
        return np.r_[np.cos(theta / 2.0), np.sin(theta / 2.0) * axis]

    @staticmethod
    def _quat_log_short_arc(q):
        q = q / (np.linalg.norm(q) + 1e-12)
        if q[0] < 0.0:
            q = -q
        v = q[1:]
        nv = np.linalg.norm(v)
        if nv < 1e-9:
            return 2.0 * v
        return 2.0 * np.arctan2(nv, q[0]) * v / nv

    def run_episode(self, max_steps=500):
        """执行一个完整 episode"""

        for step in range(max_steps):
            # 每 policy_freq 步做一次策略推理
            if step % (self.ctrl_freq // self.policy_freq) == 0:
                obs = self._get_observation()
                self.obs_buffer.append(obs)

                if len(self.obs_buffer) >= 2:
                    # Diffusion Policy 推理 (~50ms on GPU)
                    obs_dict = self._format_obs(self.obs_buffer[-2:])
                    with torch.no_grad():
                        action_seq = self.policy.predict_action(obs_dict)
                    # action_seq: (8, 6) 未来 8 步的末端位姿增量
                    self.action_queue = action_seq.cpu().numpy()
                    self.action_idx = 0

            # 从队列取当前动作
            if hasattr(self, 'action_queue') and self.action_idx < len(self.action_queue):
                delta_pose = self.action_queue[self.action_idx]
                # 每 ctrl_freq/policy_freq 步前进一个动作
                if step % (self.ctrl_freq // self.policy_freq // self.action_horizon) == 0:
                    self.action_idx += 1
            else:
                delta_pose = np.zeros(6)

            # 计算目标位姿。delta_pose 的后三维是 so(3) 旋转向量,
            # 姿态不能像欧氏坐标一样直接相减。
            p_current = self.robot.get_ee_position()
            q_current = self.robot.get_ee_quaternion()  # [w, x, y, z]
            p_d = p_current + delta_pose[:3]
            q_delta = self._rotvec_to_quat(delta_pose[3:])
            q_d = self._quat_mul(q_delta, q_current)

            # --- 底层阻抗控制 (1kHz) ---
            e_pos = p_d - p_current
            q_err = self._quat_mul(q_d, self._quat_conj(q_current))
            e_ori = self._quat_log_short_arc(q_err)

            # 安全裁剪 (关键,但不是完整安全证明;仍需 F06 监控层)
            e_pos = np.clip(e_pos, -self.max_pos_error, self.max_pos_error)
            e_ori = np.clip(e_ori, -self.max_ori_error, self.max_ori_error)
            e_x = np.concatenate([e_pos, e_ori])

            x_dot = self.robot.get_ee_velocity()
            F_cmd = self.K_d @ e_x - self.D_d @ x_dot
            tau = self.robot.J.T @ F_cmd + self.robot.gravity()
            tau_max = np.array([87, 87, 87, 87, 12, 12, 12], dtype=float)
            tau = np.clip(tau, -tau_max, tau_max)

            self.robot.step(tau)

    def _get_observation(self):
        return {
            'ee_pos': self.robot.get_ee_position(),
            'ee_quat': self.robot.get_ee_quaternion(),
            'force_torque': self.robot.get_ft_sensor(),
            'joint_pos': self.robot.get_joint_positions(),
        }

反事实推理:如果 Diffusion Policy 直接输出关节力矩而非末端位姿增量会怎样? - 力矩输出的动作空间是 \(\mathbb{R}^7\)(7D),位姿增量是 \(\mathbb{R}^6\)(6D)——维度差不多 - 但接触任务中的力矩输出通常需要 100+ Hz 甚至更高频的闭环和独立安全监控,而 Diffusion 推理需要 50-100ms - 50ms 的力矩延迟在接触时 = 50N+ 的力冲击(K_env=10000 N/m 时) - 位姿增量通过底层 1kHz 阻抗"翻译"为安全力矩,延迟被阻抗环吸收 - 结论:Diffusion Policy 的推理延迟决定了它必须输出高层命令(位姿),不能输出低层命令(力矩)

CRISP 标准架构

Python GPU 节点 ──10 Hz──> target_pose 话题
     |                            |
     | (Diffusion Policy          | (DDS/ROS2)
     |  推理 ~50ms)               |
     v                            v
观测采集                    C++ 控制器 (1 kHz)
  - 相机图像                  - 笛卡尔阻抗
  - 关节状态                  - 误差裁剪
  - 力传感器                  - 安全监控
                                |
                                v
                           机器人硬件

Diffusion Policy vs VICES vs SERL

对比项 Diffusion Policy VICES SERL
学习方法 模仿学习 RL (PPO/SAC) RL (RLPD)
需要数据 50-200 demo 仿真交互 20 demo + 25min 真机
策略输出 末端位姿序列 阻抗参数 末端位姿增量
底层控制 固定阻抗 可变阻抗 固定阻抗
泛化能力 高(多模态) 中-低
力控精度 高(阻抗可调)

⚠️ 常见陷阱

💡 概念误区:认为 Diffusion Policy 能处理任意力控任务
   新手想法:"效果很好,力控也应该行"
   实际上:Diffusion Policy 擅长运动规划(到哪里/走什么路径),
          力控精度取决于底层阻抗控制器。
          需要 1N 精度力控的任务 -> 需要 VICES 的可变阻抗。
   正确理解:Diffusion 解决"策略",阻抗解决"力"。
🧠 思维陷阱:认为 demo 越多越好
   新手想法:"1000 个 demo 肯定比 50 个好"
   实际上:1000 个低质量 demo 不如 50 个高质量 demo。
          Diffusion Policy 学数据分布——矛盾行为导致"犹豫"。
   正确做法:50-100 个高质量、有代表性的 demo。

练习

  1. 频率分析:Diffusion 10 Hz,底层 1 kHz。两次策略输出间底层执行多少步?位姿跳变 5mm 时力冲击多大(K=300 N/m)?
  2. ⭐⭐ 底层参数敏感性:在 CRISP 仿真中测试 K=100,300,500 N/m 的效果。
  3. ⭐⭐ 理论对比:对 1N 精度装配任务,Diffusion(固定阻抗)和 VICES(可变阻抗)哪个更合适?如果任务涉及多种形状零件呢?

F9.5 FALCON 力课程——双智能体 RL ⭐⭐⭐

动机——人形 loco-manipulation 的力适应

FALCON(Zhang et al., CMU LeCAR Lab, L4DC 2026 Oral;arXiv 2025)让人形机器人在行走同时承受外力。

双智能体架构

Agent L(下身 Locomotion):
  观测: 体姿态/速度/上身力矩反馈
  动作: 12D 关节位置(腿)
  训练: Isaac Lab, 4096 并行

Agent M(上身 Manipulation):
  观测: 臂关节状态/末端位姿/外力估计
  动作: 4-6D 关节位置(臂)
  训练: 叠加在冻结 Agent L 之上

训练流程:
  Phase 1: 训练 Agent L(无外力行走)
  Phase 2: 冻结 Agent L,训练 Agent M
  Phase 3: 联合微调(可选)

力课程

阶段 1: f_ext = 0 N       -> 基本运动协调
阶段 2: f_ext ≈ 20 N      -> 轻微力补偿(约 2 kgf)
阶段 3: f_ext ≈ 50 N      -> 步态调整抵抗外力(约 5 kgf)
阶段 4: f_ext ≈ 100 N     -> 大幅调整体姿/步态/臂配置(约 10 kgf)

每阶段训练到收敛后才进入下一阶段

反事实推理:如果直接用约 100 N(约 10 kgf)训练?初始策略不知道应对大外力 -> 频繁摔倒 -> 有效探索时间极短 -> RL 学不到有用策略。力课程的本质:把困难问题分解为渐进的简单问题

力估计

力估计网络:
  输入: [q(12), dq(12), tau_measured(12)]
  输出: f_ext_hat(3)
  训练: 仿真中用已知 f_ext 监督学习
  精度: ~1-2N (5kg 负载下 < 5%)

结果

配置 最大外力 最大速度
Unitree G1 ~100 N(约 10 kgf) 0.5 m/s
Unitree H1 ~100 N(约 10 kgf) 0.8 m/s
Booster T1 ~100 N(约 10 kgf) 0.6 m/s

⚠️ 常见陷阱

💡 概念误区:认为双智能体不如端到端
   新手想法:"联合优化应该更好"
   实际上:人形 20-30+ DOF,端到端动作空间太大。
          双智能体分为 12D + 6D,每个更容易学。
          分开训练还允许复用 Agent L。
🧠 思维陷阱:认为力课程只适用于人形
   新手想法:"FALCON 是人形方法"
   实际上:力课程思想是通用的 RL 训练技巧:
          装配: 间隙 1mm -> 0.1mm
          打磨: 力 2N -> 20N
          擦拭: 光滑 -> 粗糙

练习

  1. 课程设计:为 Franka peg-in-hole 设计 4 阶段力课程。
  2. ⭐⭐ chicken-and-egg 问题:Agent L 训练时 Agent M 还没训练,如何处理上身力矩反馈?
  3. ⭐⭐⭐ 跨章综合题:为 Go2 四足"前腿推门"选择动作空间(VICES/关节位置/末端力),分析优劣并设计力课程。

F9.6 sim-to-real 在力控中的独特挑战 ⭐⭐⭐

动机——力仿真比运动仿真难得多

回顾 P02:sim-to-real gap 的三大来源。对力控任务,这些 gap 被**放大**。

力控 sim-to-real 的穷举分类

维度 Gap 来源 量级 影响
接触模型 Hertz vs 弹塑性 力误差 20-50% 力跟踪差
接触参数 K_e, D_e 未知 变化 10x 阻抗不匹配
摩擦 库仑 vs Stribeck 动/静摩擦比 0.6-0.8 滑动不准
传感器 噪声/迟滞/温漂 2-5N 力反馈不准
执行器 摩擦/柔性/齿隙 5-10% 力矩偏差
几何 mesh精度/粗糙度 0.1-1mm 接触时机错误

应对方案

方案 1:Domain Randomization(DR)

随机化接触参数:
  K_contact: [1000, 100000] N/m
  mu: [0.3, 1.0]
  F_noise ~ N(0, sigma^2), sigma 属于 [0, 5] N
  tau_delay: [0, 5] ms

效果: 策略对参数变化鲁棒
代价: 仿真性能下降 10-30%(保守策略)

跨领域类比:DR 像在暴风雨中练习开车——你不是让暴风雨消失,而是让自己在任何天气都能开。真实世界只是练习过的天气中的一种。

方案 2:System Identification

测量真实参数让仿真匹配:
  1. 力传感器 -> 测 K_e
  2. 自由运动 -> 辨识执行器摩擦
  3. 多次接触 -> 辨识 mu

优点: 仿真更精确
缺点: 每个新环境需重新辨识

方案 3:Sim-to-Real Fine-tuning

1. 仿真预训练(百万步+DR)
2. 部署真机
3. 少量真机数据(几百步)微调

开源力控仿真生态

框架 接触模型 力传感器 适用
MuJoCo 3.x 凸接触, Newton sensordata 通用力控
Isaac Lab GPU 并行 内置 大规模 RL
RoboSuite MuJoCo 后端 内置 benchmark
Genesis 统一引擎, 43M FPS 开发中 下一代

接触模型误差的定量分析 ⭐⭐⭐

sim-to-real gap 在力控中的核心来源是**接触模型误差**。以下系统分析三类主流接触模型的误差特性。

三类接触模型对比

模型 公式 参数 MuJoCo 实现 误差来源
线弹性 \(f_n = K_e \cdot \delta\) \(K_e\) solref[0](刚度) 真实接触非线性
Hertz \(f_n = K_H \cdot \delta^{3/2}\) \(K_H, R\) 不直接支持 只适用弹性变形
Hunt-Crossley \(f_n = K_e \delta^n (1 + D \dot{\delta})\) \(K_e, D, n\) solref[1](阻尼) \(n, D\) 难以辨识

MuJoCo 3.x 的接触模型细节

MuJoCo 默认: 凸优化接触模型 (不是脉冲/弹簧)
  求解器: Newton (3.0+, 替代了旧的 PGS)
  接触刚度: 由 solref 控制
    solref = [timeconst, dampratio]
    等效刚度 K_eff = 1 / (timeconst^2 * h^2)  (h = timestep)
    等效阻尼 D_eff = 2 * dampratio * sqrt(K_eff * m_eff)

  关键参数与力精度的关系:
    timestep = 0.002s (默认) -> 接触力误差 ~20-30%
    timestep = 0.001s        -> 接触力误差 ~10-15%
    timestep = 0.0005s       -> 接触力误差 ~5-8%
    timestep = 0.0002s       -> 接触力误差 ~2-3% (但计算量 10x)

经验法则: 力控任务的 timestep 至少要 0.001s (1kHz)
          精度要求高时用 0.0005s (2kHz)

定量分析:仿真力 vs 真实力的典型差异

实验: Franka 末端以不同速度接触铝板, 记录峰值力

          |  v=0.01m/s  |  v=0.05m/s  |  v=0.1m/s  |
真实      |    2.1 N     |    8.5 N     |   18.3 N    |
MuJoCo默认|    1.5 N     |    5.2 N     |   11.7 N    |  误差 ~36%
MuJoCo校准|    1.9 N     |    7.8 N     |   16.1 N    |  误差 ~12%
Isaac Lab |    1.8 N     |    7.1 N     |   14.5 N    |  误差 ~21%

观察:
  1. 所有仿真器在低速时较准,高速时偏差增大
  2. 这是因为真实接触有弹塑性、微滑、粘弹性等效应
  3. 仿真器的线弹性模型无法捕获这些高速动态
  4. 校准 (SysID) 可以减小但无法消除误差

类比:接触模型误差就像天气预报的误差——短期(低速、小力)比较准,长期(高速、大力、动态接触)偏差增大。DR 不是让预报更准,而是让你"带伞也带防晒"——对两种天气都做好准备。

数据采集系统搭建——遥操作 + 力记录 ⭐⭐

学习型力控的瓶颈往往不是算法,而是**高质量力控数据**。以下给出完整的数据采集系统设计。

策略 效率 质量 代表 力数据特点
遥操作 DROID, RoboTurk 力曲线自然、多样
运动学示教 手把手 + 记录 力精度受人手抖动影响
自主探索 DR + RL 力曲线不自然、有碰撞
混合 中-高 SERL (20 demo + RL) 平衡效率和质量

遥操作 + 力记录系统架构

┌─── 遥操作设备 ───────────────────────────┐
│  SpaceMouse / GELLO / VR 手柄             │
│  输出: 6D 增量位姿 (200 Hz)               │
└──────────────┬────────────────────────────┘
┌─── 数据记录节点 ──────────────────────────┐
│  同步记录 (精确时间戳):                     │
│    - 关节状态 (q, dq, tau) @ 1kHz         │
│    - 末端位姿 (x_ee) @ 1kHz               │
│    - 力传感器 (f_ext) @ 1kHz              │
│    - 相机图像 @ 30Hz                       │
│    - 遥操作命令 @ 200Hz                    │
│  存储: HDF5 (robomimic 格式)              │
└──────────────┬────────────────────────────┘
┌─── 底层控制器 ────────────────────────────┐
│  笛卡尔阻抗控制 (1kHz)                     │
│  K_d 可调: 示教时用低刚度 (50-100 N/m)     │
│  力传感器: 偏置自动校准 (每次示教前)         │
└───────────────────────────────────────────┘

力传感器数据质量保证

"""
力传感器数据预处理管线
"""
import numpy as np
from scipy.signal import butter, filtfilt

class ForceDataProcessor:
    """力传感器数据质量保证"""

    def __init__(self, fs=1000):
        self.fs = fs
        # 低通滤波器 (去高频噪声)
        self.b, self.a = butter(4, 40 / (fs / 2), btype='low')

    def calibrate_bias(self, free_motion_data, duration=2.0):
        """
        偏置校准: 自由运动时力传感器应读 0
        在每次示教前调用
        """
        n_samples = int(duration * self.fs)
        self.bias = np.mean(free_motion_data[:n_samples], axis=0)
        self.noise_std = np.std(free_motion_data[:n_samples], axis=0)
        print(f"偏置: {self.bias}")
        print(f"噪声 std: {self.noise_std}")
        return self.bias

    def process(self, raw_force):
        """完整预处理: 去偏置 -> 滤波 -> 异常检测"""
        # 1. 去偏置
        force = raw_force - self.bias

        # 2. 低通滤波 (40Hz 截止)
        force_filtered = filtfilt(self.b, self.a, force, axis=0)

        # 3. 异常检测 (超过 5 sigma 的点标记为异常)
        anomaly_mask = np.any(
            np.abs(force_filtered) > 5 * self.noise_std, axis=1
        )

        return force_filtered, anomaly_mask

    def compute_quality_metrics(self, demo_forces):
        """评估一批 demo 的力数据质量"""
        metrics = {}
        for i, f in enumerate(demo_forces):
            metrics[f'demo_{i}'] = {
                'snr': np.mean(np.abs(f)) / np.mean(self.noise_std),
                'max_force': np.max(np.abs(f)),
                'smoothness': np.mean(np.abs(np.diff(f, axis=0))),
                'has_contact': np.any(np.abs(f) > 3 * self.noise_std),
            }
        return metrics

数据采集的关键经验

常见问题 根因 解决方案
力数据全是噪声 偏置未校准 每次示教前校准 2s
力数据有毛刺 高频振动 40Hz 低通滤波
接触力缺失 力传感器延迟 确认传感器和控制器同步
demo 间力曲线差异大 操作员手法不一致 固定操作流程+多人采集
存储文件过大 图像未压缩 JPEG 压缩,力数据保留 float32

⚠️ 常见陷阱

⚠️ 编程陷阱:MuJoCo 默认接触参数不适合力控
   错误做法:使用默认参数
   现象:仿真力跟踪好,真机差
   正确做法:减小 timestep、增加求解器迭代、SysID 校准
💡 概念误区:认为 sim-to-real gap 可以完全消除
   新手想法:"仿真足够精确就能消除 gap"
   实际上:真实世界有无限复杂性,仿真永远无法完全匹配。
   正确思维:不追求"消除 gap",而追求"对 gap 鲁棒"。

练习

  1. DR 设计:为 Franka peg-in-hole 设计 DR 参数表,列出范围和分布类型。
  2. ⭐⭐ 接触参数敏感性:MuJoCo 中方块推平面,K_contact = 1e3, 1e4, 1e5, 1e6,记录力曲线。
  3. ⭐⭐⭐ SERL vs FALCON sim-to-real 策略对比:分析真机训练 vs 仿真+DR+zero-shot 的 trade-off。

F9.7 开源框架实战 ⭐⭐

robosuite 力控配置实战 ⭐⭐

robosuite (Stanford) 是学习型力控的标准 benchmark 平台。以下给出力控任务的完整配置。

"""
robosuite 力控任务完整配置
"""
import robosuite as suite
from robosuite.controllers import load_controller_config
import numpy as np

# === 配置 1: 操作空间阻抗控制 (推荐力控任务) ===
osc_config = load_controller_config(default_controller="OSC_POSE")

# 力控关键参数修改
osc_config['kp'] = 150             # 默认 300, 力控任务需降低
osc_config['damping_ratio'] = 1.0  # 临界阻尼
osc_config['impedance_mode'] = 'variable_kp'  # 允许可变刚度
osc_config['kp_limits'] = [10, 500]  # K_d 范围
osc_config['control_delta'] = True   # 增量控制 (推荐)
osc_config['input_max'] = 0.05       # 5cm 最大增量
osc_config['input_min'] = -0.05
osc_config['output_max'] = [0.05, 0.05, 0.05, 0.5, 0.5, 0.5]
osc_config['output_min'] = [-0.05, -0.05, -0.05, -0.5, -0.5, -0.5]

# === 创建环境 ===
env = suite.make(
    env_name="PegInHole",
    robots="Panda",
    controller_configs=osc_config,
    has_renderer=True,
    has_offscreen_renderer=True,
    use_camera_obs=True,
    camera_names=["agentview", "robot0_eye_in_hand"],
    camera_heights=84,
    camera_widths=84,
    reward_shaping=True,     # 稠密奖励
    control_freq=20,         # 策略频率 (底层仍 500Hz)
    horizon=500,
)

# === 力传感器数据获取 ===
obs = env.reset()
action_low, action_high = env.action_spec
action_dim = action_low.shape[0]
# 不同 impedance_mode 的动作维度不同:
# fixed 通常只含末端位姿增量,variable_kp 会额外加入刚度项,
# variable 还可能加入阻尼/阻抗参数。不要硬编码 7 维。
for step in range(500):
    action = np.random.uniform(action_low, action_high, size=action_dim)
    obs, reward, done, info = env.step(action)

    # 力传感器数据
    ee_force = obs['robot0_eef_force']       # (3,) 末端力
    ee_torque = obs['robot0_eef_torque']     # (3,) 末端力矩

    # 关节数据
    joint_pos = obs['robot0_joint_pos']       # (7,)
    joint_vel = obs['robot0_joint_vel']       # (7,)

    print(f"Step {step}: force={ee_force}, torque={ee_torque}")

robomimic 力控训练配置 ⭐⭐

"""
robomimic: 从 demo 训练 Diffusion/BC 力控策略
"""
# Step 1: 数据收集 (遥操作)
# python robomimic/scripts/collect_human_demonstrations.py \
#   --environment PegInHole \
#   --robots Panda \
#   --controller OSC_POSE \
#   --directory demo_data/

# Step 2: 数据转换
# python robomimic/scripts/dataset_states_to_obs.py \
#   --dataset demo_data/peg_insertion.hdf5 \
#   --output_name demo_data/peg_insertion_obs.hdf5 \
#   --obs_keys robot0_eef_pos robot0_eef_quat robot0_eef_force \
#              robot0_joint_pos robot0_joint_vel

# Step 3: 训练配置 (JSON)
training_config = {
    "algo_name": "diffusion_policy",
    "experiment": {
        "name": "peg_insertion_force",
        "validate": True,
        "save": {"enabled": True, "every_n_epochs": 50},
        "rollout": {"enabled": True, "n": 20, "horizon": 500},
    },
    "train": {
        "data": "demo_data/peg_insertion_obs.hdf5",
        "output_dir": "trained_models/",
        "num_epochs": 600,
        "batch_size": 64,
        "seq_length": 10,          # 观测序列长度
    },
    "observation": {
        "modalities": {
            "obs": {
                "low_dim": [
                    "robot0_eef_pos",
                    "robot0_eef_quat",
                    "robot0_eef_force",    # 力观测 (关键!)
                    "robot0_joint_pos",
                    "robot0_joint_vel",
                ],
            }
        },
    },
    "algo": {
        "horizon": 16,
        "n_action_steps": 8,
        "n_obs_steps": 2,
        "unet": {
            "down_dims": [256, 512, 1024],
        },
        "noise_scheduler": {
            "num_train_timesteps": 100,
        },
    },
}

SERL 仿真模式配置 ⭐⭐

# SERL 安装和仿真训练
git clone https://github.com/rail-berkeley/serl.git
cd serl

# 安装 (推荐 conda 环境)
pip install -e serl_launcher
pip install -e serl_robot_infra

# 仿真训练 (PCB 插入)
python serl_launcher/serl_launcher/train.py \
    --config serl_launcher/configs/peg_insert_sim.py \
    --learner \
    --actor \
    --render \
    --utd_ratio=20 \
    --batch_size=256 \
    --max_steps=100000

# 关键配置参数
# peg_insert_sim.py:
#   controller = "OSC_POSE"
#   control_freq = 20
#   obs_keys = ["eef_pos", "eef_quat", "ft_sensor", "joint_pos"]
#   action_space = "delta_eef"  (末端增量)
#   reward = sparse + shaping
#   demo_path = "demos/peg_20demos.pkl"

DROID 数据集力控分析

"""
DROID 数据集: 分析力传感器数据分布
"""
import h5py
import numpy as np

# DROID 包含 76k+ 遥操作轨迹
# 每条轨迹包含: RGB, depth, joint_states, forces

def analyze_droid_forces(hdf5_path):
    """分析 DROID 数据集的力分布"""
    with h5py.File(hdf5_path, 'r') as f:
        forces = []
        for demo_key in list(f['data'].keys())[:100]:  # 采样 100 条
            demo = f[f'data/{demo_key}']
            if 'obs/force_torque' in demo:
                ft = demo['obs/force_torque'][:]
                forces.append(ft)

        all_forces = np.concatenate(forces, axis=0)

        print(f"力范围: [{all_forces.min():.1f}, {all_forces.max():.1f}] N")
        print(f"力均值: {all_forces.mean(axis=0)}")
        print(f"力标准差: {all_forces.std(axis=0)}")
        print(f"接触率: {(np.abs(all_forces).max(axis=1) > 2.0).mean():.1%}")

        # 典型结果:
        # 力范围: [-45.2, 52.8] N
        # 力均值: [-0.3, 0.1, -2.8, ...]  (z 方向有重力偏置)
        # 接触率: 34% (约 1/3 的时间步有显著接触力)

⚠️ 常见陷阱

⚠️ 编程陷阱:robosuite OSC_POSE 默认 kp=300 过高
   错误做法:使用默认参数做力控
   现象:接触时力冲击大,策略学不到柔顺行为
   正确做法:kp=100-200,damping_ratio=1.0
   自检方法:空载时检查末端是否可以被 5N 力推动 > 3mm
⚠️ 编程陷阱:robomimic 数据缺少力观测
   错误做法:收集 demo 时忘记加 force 到 obs_keys
   现象:训练出的策略不使用力信息 -> 接触不敏感
   正确做法:dataset_states_to_obs 时显式加 robot0_eef_force
💡 概念误区:认为更多 demo 总是更好
   新手想法:"DROID 有 76k 轨迹,全用上肯定最好"
   实际上:DROID 覆盖了上百种任务和环境。
          对特定力控任务(如 peg-in-hole),只有 ~100 条相关轨迹。
          混入不相关数据会降低策略精度。
   正确做法:先筛选任务相关的 demo,再训练。
            50 条高质量任务相关 demo > 5000 条混杂 demo。

练习

  1. robosuite 入门:运行 PegInHole,记录力传感器数据。绘制接触过渡时的力曲线。
  2. ⭐⭐ SERL 仿真训练:训练 peg_insert_sim,修改 UTD 从 20 到 5 观察收敛速度和最终成功率差异。
  3. ⭐⭐ Diffusion Policy 力分析:在 robomimic 中训练 Square 任务。分别用 (a) 有力观测 和 (b) 无力观测 训练,对比 20 次评估成功率和力峰值。
  4. ⭐⭐⭐ 跨章综合题:设计一个完整的学习型力控管线,从数据采集(遥操作+力记录)到训练(Diffusion Policy)到部署(底层阻抗+安全监控)。画出系统架构图,标注每个模块来自 F01-F09 的哪个章节。

本章小结

知识点 核心内容 难度 关联章节
F9.1 为什么需要学习型力控 经典方法三个天花板 F01-F08
F9.2 VICES 阻抗参数作为 RL 动作空间 ⭐⭐ F03, F04
F9.3 SERL 25 分钟真机学习 ⭐⭐ F04
F9.4 Diffusion Policy 扩散策略+底层阻抗 ⭐⭐ F04, F05
F9.5 FALCON 双智能体 RL,力课程 ⭐⭐⭐ F07, F08
F9.6 sim-to-real 力仿真挑战,DR/SysID ⭐⭐⭐ P02
F9.7 开源框架 robomimic/robosuite/SERL/DROID ⭐⭐

累积项目:本章新增模块

Mini-ForceControl 项目进度:
  F01-F06: 固定基座力控全栈
  F07: WBC-QP 框架
  F08: MPC+WBC 联合力控
  F09: 学习型力控 <-- 本章新增
       - VICES peg-in-hole 仿真
       - SERL sim 模式训练
       - Diffusion + 底层阻抗演示
       - DR 参数敏感性实验

延伸阅读

资源 类型 难度 内容
Martin-Martin et al. 2019 "VICES" IROS 论文 ⭐⭐ 阻抗参数动作空间
Luo et al. 2024 "SERL" ICRA 论文 ⭐⭐ 25 分钟真机学习
Luo et al. 2024 "HIL-SERL" arXiv 论文 ⭐⭐⭐ 人类在环 RL
Chi et al. 2023 "Diffusion Policy" RSS 论文 ⭐⭐⭐ 扩散策略
Zhang et al. 2025 "FALCON" L4DC 论文 ⭐⭐⭐ 人形力课程 RL
Buchli et al. 2011 IJRR 论文 ⭐⭐⭐ 变阻抗学习先驱
robosuite 文档 文档 ⭐⭐ 力控 benchmark
SERL GitHub 代码 ⭐⭐ 真机 RL 框架

故障排查手册

症状 可能原因 排查步骤 相关章节
RL reward 不涨 奖励缩放失衡 1. 打印各分项 2. 检查 task vs reg 比例 F9.2
VICES 学到 K=0 能耗正则过大 1. 减小 w_K 2. 设 K_min > 0 F9.2
SERL 不收敛 demo 质量差 1. 检查 demo 一致性 2. 增加到 30-50 F9.3
Diffusion 力控不准 底层阻抗不匹配 1. 调 K_d 2. 检查策略频率 F9.4
sim-to-real 力误差大 接触参数 gap 1. SysID 2. 加大 DR 3. fine-tune F9.6
MuJoCo 力不稳定 timestep 过大 1. 减小 dt 2. 增加迭代 F9.6
robosuite 阻抗过硬 默认 kp 高 1. 降 kp 到 150 F9.7