跳到主要内容
交互模式

1. 执行器与 PD 控制

本章目标

  • 理解位置误差、速度误差、P 增益、D 增益各自在干什么
  • 能在 MuJoCo 里把一个 hinge 关节从任意初始角度稳定控制到目标角度
  • 能画出一张关节角随时间的响应曲线,并解释过冲 / 欠阻尼 / 稳态误差
  • 知道为什么工业上几乎所有执行器最低层都是 PD / PID

前置阅读

1.1 执行器

执行器(Actuator) 是机器人技术中的核心组件,可以被直观地理解为系统的“肌肉”。它的核心作用是将某种形式的能量(电力、液压、气压等)转化为物理运动,从而改变受控对象的状态(例如让机器人能够行走、抓取等)。

1.1.1 工作原理

执行器的基本原理是把弱电指令放大成机械动作,再通过传感器把实际状态回传给控制器。可以拆成四步:

  1. 输入信号:上层控制器(PC、嵌入式 MCU 或专用驱动板)按固定频率把目标值(位置、速度或力矩)发给执行器,常见承载是 PWM、CAN、EtherCAT 等不同协议。
  2. 能量转换:执行器内部机构把输入信号放大并转换成另一种能量形式——电动机把电流经磁场转成转矩,液压缸把油压转成推力,气动肌肉把气压转成收缩力。
  3. 产生动作:输出端体现为位移、转角、推力或扭矩,直接作用在关节、轮子或末端执行器上。
  4. 反馈回路:现代执行器几乎都内嵌编码器、电流传感器或力矩传感器,把实际状态回传给控制器,便于构成反馈回路。
执行器工作流程:输入信号 → 能量转换 → 产生动作 → 反馈回路
执行器工作流程:输入信号 → 能量转换 → 产生动作 → 反馈回路

1.1.2 执行器分类

按能量来源,常见执行器可以分成三大类,如表 1 所示:

类别代表典型场景特点
电动有刷直流、无刷直流(BLDC)、步进机械臂、足式机器人、无人机控制精度高、响应快,具身智能场景里的绝对主流
液压Boston Dynamics Atlas重载、高爆发功率密度最高,但贵、漏油、噪声大
气动软体抓手、McKibben 人工肌肉柔性操作、仿生轻、便宜、本征柔顺,但控制精度差
常见执行器按能量来源的三大类

电动执行器结构简单、控制精度高、响应快,配合编码器和现代电流环能做到毫秒级的位置 / 速度 / 力矩控制,是具身智能场景里的绝对主流,从机械臂到足式机器人几乎都选这条路。

液压执行器靠高压油驱动活塞,功率密度比电机高出一个数量级,能扛重载和瞬时冲击;代价是系统复杂、贵、容易漏油、噪声大,只在 Atlas 这类对功率密度极致追求的平台上才常见。

气动执行器用压缩空气驱动,本征柔顺、便宜、轻,适合软体抓取和仿生肌肉;但空气可压缩性大,闭环控制精度差,难以做到亚毫米级定位。

电动执行器又分为有刷直流、无刷直流(BLDC)、步进电机和伺服电机等类型,其中无刷直流以其高效率、长寿命和低维护需求成为现代机器人设计的首选,如图 2 所示:

常见电动执行器示意图
常见电动执行器示意图

1.1.3 齿轮箱

齿轮箱(Gearbox),在机器人和机械工程领域通常被称为减速器(Reducer)或传动装置,我们可以把它直观地理解为机器人的变速自行车齿轮系统

它的核心功能是:连接在动力源(如电机)和执行端(如机械臂关节、车轮)之间,通过内部不同大小齿轮的物理啮合,来改变旋转的“速度”和“扭力(扭矩)”。

机器人之所以几乎离不开它,是因为 BLDC 等常见电机"转得快、力矩小"(几千 RPM、零点几 N·m),而关节需要的是"慢而有力"(十几 rad/s、几 N·m 到几十 N·m),中间必须经过一级换算:

齿轮传动动画:主动轮与从动轮按固定传动比反向旋转,输出端转得更慢但更有力
齿轮传动动画:主动轮与从动轮按固定传动比反向旋转,输出端转得更慢但更有力

其中各符号含义如下:

  • :电机端输出的扭矩(N·m)与角速度(rad/s)
  • :经齿轮箱减速后关节端的扭矩与角速度
  • 减速比(Gear Ratio),电机端转速与关节端转速的比值,机器人关节常见 6:1 ~ 160:1
  • 传动效率(Efficiency),输出功率 / 输入功率,行星齿轮约 90%、谐波减速器约 70 ~ 80%
  • :电机转子的转动惯量(kg·m²)
  • 反射惯量(Reflected Inertia),电机转子惯量经齿轮箱放大后等效到关节端的值

一套减速比为 的齿轮箱意味着力矩放大 倍,转速缩小 倍。

1.2 控制系统

控制是一个宏观的概念,它描述的是为了使系统的输出达到期望的状态,而对系统输入进行干预的过程。换句话说,它的核心任务是解决:“我们该给执行器下达什么样的指令,才能让物理对象变成我们想要的样子?”。常见的控制方法包括开环控制和闭环控制,其中闭环控制又被称为反馈控制,因为它依赖于系统状态的实时反馈来调整输入。

1.2.1 开环控制

开环控制(Open-loop Control) 的控制量只依赖目标 和时间 ,不读取系统当前状态 ,如式 所示:

家用洗衣机、微波炉、按预设脉冲数旋转的步进电机都是典型代表——指令序列在程序里写死,执行端实际走到哪里不会反过来影响后续动作。

开环控制:指令单向下发,执行端状态不回传
开环控制:指令单向下发,执行端状态不回传

开环控制的优点是简单,不需要传感器建立反馈通路。但缺点是无法适应任何外界扰动,例如机械臂收到"转到 90°"的开环指令,一旦碰到摩擦、负载或障碍物,就会停在偏离 90° 的位置,并且不会自我修正。

1.2.2 闭环控制

闭环控制(Closed-loop Control) 又称反馈控制(Feedback Control),控制量根据实测误差 实时计算,如式 所示:

每个采样周期,传感器测出当前 ,控制器算出 并输出 ,执行器把 作用到被控对象上,下一拍传感器再测一次状态——控制器 → 执行器 → 被控对象 → 传感器 → 控制器 由此闭合成回路。

闭环控制:传感器把实测状态回传,控制器据此修正
闭环控制:传感器把实测状态回传,控制器据此修正

闭环的关键能力是自我纠错:扰动来自哪里并不重要——多挂了 1 kg 负载、电池电压跌了、桌面把关节顶了一下,只要它表现为偏离目标的 ,控制器在下一拍就能感知并修正。

后续讨论的 Bang-Bang 和 PID 控制都属于闭环控制的范畴,区别在于它们对 的定义不同。Bang-Bang 只看误差的符号,PID 则把误差的大小、历史和变化趋势都考虑进来,形成一个更复杂的反馈策略。

1.3 Bang-Bang 控制

Bang-Bang 控制(又称双位控制或开关控制)是闭环控制里最简单的一种,核心公式如式 所示:

Bang-Bang 控制:仅按误差符号在 ±τ_max 间切换,关节穿过目标点形成极限环
Bang-Bang 控制:仅按误差符号在 ±τ_max 间切换,关节穿过目标点形成极限环

Bang-Bang 的逻辑是:只看误差 的符号,完全不管它的大小——如果关节在目标左侧(),就全力右拉 ;如果在目标右侧(),就全力左拉 ;如果正好在目标点(),就不出力

类比开车,油门和刹车各有一个踏板——要么踩到底,要么完全松开。每当系统穿越目标点,执行器在极短时间里从 切换到 ,机械结构上常伴随一声清脆的换向冲击声(Bang!),名字也由此而来。

尽管听上去很粗暴,但只要被控对象足够"慢",Bang-Bang 就是最便宜也最可靠的解。家用空调是最直观的例子:室温低于设定 → 开压缩机 → 升温到设定上方一两度 → 关压缩机 → 自然耗散 → 跌回设定下方 → 再开。整个循环以分钟为单位,开 / 关切换瞬间的小幅温度波动我们完全察觉不到,反而节约了复杂的传感器和调参成本。

总的来说,当被控对象的响应时间远大于切换抖动的时间,Bang-Bang 就是最优解

然而,在机器人控制场景中,一个轻量化关节的机械时间常数往往只有几十毫秒,电机扭矩切换却几乎是瞬间,两个时间尺度倒了过来。此时,Bang-Bang 就会在目标附近形成一个极限环(Limit Cycle),关节永远停不下来,电流也在 之间反复切换,对机械结构的磨损和能量效率都是灾难性的。

极限环时域图:关节在 q_d 两侧以幅度 Δq 周期摆动
极限环时域图:关节在 q_d 两侧以幅度 Δq 周期摆动

1.4 PID 控制

PID 控制(Proportional-Integral-Derivative Control)是工业控制领域应用最广泛、最经典的一种反馈控制算法,其核心公式如式 所示:

具体来说,PID 控制可以拆开成三个分量,每一项分别对应当前、过去和未来的误差。可以想象我们在驾驶汽车并试图停在一条精准的白线上:

1. 比例(Proportional,P) —— "当前的误差"

  • 逻辑:误差越大,输出越大。
  • 在车里:离白线还有 10 米,就大脚踩油门;离白线还有 1 米,就轻踩油门。
  • 缺点:仅靠 P 无法消除静差。当车子非常靠近白线时,输出变得极小,可能由于摩擦力,车子还没到白线就停下了。

2. 积分(Integral,I) —— "过去的累积误差"

  • 逻辑:只要误差一直存在,输出就会随时间不断累加,直到误差消失。
  • 在车里:如果车子卡在离白线 10 厘米的地方不动了,积分项会感知到"误差一直存在",缓慢增加油门,直到车子最终压到白线上。
  • 缺点:容易导致超调(Overshoot)。因为积分有惯性,当车子到达白线时,累积的动力可能还没撤销,导致车子冲过头。

3. 微分(Derivative,D) —— "未来的误差趋势"

  • 逻辑:预测误差的变化趋势。误差减小得越快,它产生的"阻力"就越大,起到刹车的作用。
  • 在车里:即使离白线还有一段距离,但如果当前速度非常快(误差减小得极快),微分项会命令我们"提前减速"或"踩刹车",防止冲过头。
  • 缺点:对噪声非常敏感。如果传感器数据跳变厉害,微分项会产生剧烈的波动。
PID 三项分解:现在(P)、过去(I)、未来(D) 对阶跃响应的影响
PID 三项分解:现在(P)、过去(I)、未来(D) 对阶跃响应的影响

1.5 PD 控制

在工业与机器人控制里,真正启用积分项的场景其实并不多,主要原因包括积分饱和、弹簧-阻尼器的物理等效性、以及重力前馈的替代等因素,因此实际应用中 PD 控制反而更常见。

1.5.1 积分饱和

积分饱和(Integral Windup) 指当误差长时间无法消除时,积分项持续累加、最终远超执行器物理上限的现象。在纯数学模型里它只是个变大的数值,但在物理世界里执行器的力矩有上限,环境中又随处是障碍物——一旦误差被卡住,积分项就会进入失控状态,并在解除卡住的一瞬间集中释放。

设想一个关节目标角度是 90°,在 45° 时被桌面卡住:

  • 使用 PD 时,关节会保持一个恒定推力(P 项相当于一根被拉伸的弹簧),安全地顶住障碍物。
  • 使用 PID 时,只要误差一直存在,积分项就会持续累加,电机收到越来越大的力矩指令,直到硬件上限。一旦障碍物突然移开,累积的积分项瞬间释放,关节会以非常剧烈的姿态甩出去——既容易损坏机器人,也带来明显的人身安全风险。
积分饱和:障碍解除瞬间累积的 I 项集中释放,关节剧烈过冲
积分饱和:障碍解除瞬间累积的 I 项集中释放,关节剧烈过冲

1.5.2 弹簧-阻尼器

现代机器人控制非常看重柔顺性(Compliance)与物理交互的安全,而 PD 律可以严格等效为一组"虚拟弹簧-阻尼器":

  • 对应虚拟弹簧的刚度(stiffness),越大关节越"硬";
  • 对应阻尼器的阻尼系数(damping),越大运动中的阻力越大、越不容易振荡。
PD 等效弹簧-阻尼器:K_p 决定回拉刚度,K_d 决定阻尼,二者共同塑造阶跃响应
PD 等效弹簧-阻尼器:K_p 决定回拉刚度,K_d 决定阻尼,二者共同塑造阶跃响应

这种物理直觉让 PD 天然契合阻抗控制(Impedance Control)——希望机器人像人手一样柔软地抓取物体时,只需调低 ,系统就自动表现出弹簧般的柔顺。而一旦引入积分项,这层纯粹的弹簧-阻尼等效性就会被破坏。

1.5.3 动力学前馈替代积分

I 项在经典控制里的主要职责是消除稳态误差,而机械臂最主要的稳态误差来源正是重力(哪怕目标角度已经近在咫尺,重力也会一直把关节往下拉,纯 P 控制永远差一截)。现代机器人学并不依靠盲目累加误差来对抗重力,而是直接利用动力学模型(Dynamics Model)精确计算,这就是计算力矩控制(Computed Torque Control),在 PD 的基础上加上一层动力学前馈:

  • 是重力补偿项,根据当前位姿直接算出抵消重力所需的力矩;
  • 是惯性矩阵与科氏力前馈。

既然稳态误差已经被精确的物理模型吃掉,积分项就变得可有可无,甚至只会额外引入相位滞后与不稳定性。

1.5.4 PD 调参

尽管 PD 律里只有两个参数 ,如何选这两个参数却是一个微妙的艺术。这两个参数直接决定关节是欠阻尼来回振荡、临界阻尼最快到达,还是过阻尼慢吞吞——同一个目标角度,参数差一倍就可能让响应时间差一个数量级。

我们可以用理论分析来指导调参,为此先用最简化的单关节模型:把关节看作一个绕固定轴转动的刚体,转动惯量为 ,忽略重力和摩擦。它的动力学方程如式 所示:

其中 是作用在关节上的总力矩——简化之后只剩 PD 控制器的输出。把 PD 律 代入(取目标静止 ),就得到 PD 控制下的关节动力学,如式 所示:

重新整理一下,这其实就是一个二阶线性系统,如式 所示:

和高中物理里"弹簧-阻尼器"的方程一模一样,

  • 就是弹簧刚度——把关节往 拉回去,越大越"硬"。
  • 就是阻尼系数——消耗动能,越大越"黏"。

由此可以直接写出两个控制工程里绕不开的量,如式 所示:

固有频率(系统本来想振多快),阻尼比(振得是否被压得住),如下表所示:

行为直观
欠阻尼(underdamped)冲过目标来回晃
临界阻尼(critical)最快、不过冲
过阻尼(overdamped)不晃,但慢吞吞

总结来说,调参的朴素做法就是先把 按"我们想要的响应快慢"选出来,再按 、取 ,就能得到一个既不晃又不慢的响应。

1.6 MuJoCo 实现

理论部分到此为止,下面把公式 写进 MuJoCo 里真的跑一遍:先用内置的 position 执行器看整体效果,再自己手搓 PD,把 的作用一个一个拆开看。

1.6.1 执行器模型

MuJoCo 用 <actuator> 标签把控制信号 ctrl[i] 翻译成作用在关节上的广义力。对单关节 PD,有三种常见写法:

标签ctrl[i] 的含义内部在算什么
<motor>直接的关节力矩 不做反馈,我们自己在 Python 里写 PD
<position kp=.. kv=..>目标位置 内部自动算
<velocity kv=..>目标速度 内部算
  • 如果我们想看清 PD 每一项、方便画曲线,用 motor + 自己写反馈。
  • 如果我们只是想让关节稳定跟踪到某个角度,用 position(写起来最短,也是 Pupper / 机械臂最常见的配置)。
  • velocity 在轮式底盘、转速环里更常见。

本章我们两种都写一遍:先用 position 看效果,再用 motor 自己手搓 PD,把 的作用一个一个拆开看。

1.6.2 单摆 PD

这一节搭一个最小能跑的 PD 例子,只要两份文件:pendulum.xml 描述物理,pd_single_joint.py 给执行器写 ctrl。我们故意在同一个 MJCF 里同时留下两种 PD 写法,Python 里靠一个开关切换,方便我们亲眼对比"MuJoCo 内置的 position 执行器"和"自己手搓的 motor + PD"是同一件事。

把下面这段存成 pendulum.xml:一根 0.5 m 长的杆子通过 hinge 挂在世界坐标系上,绕 轴转,重力向下。<actuator> 里写了两个:

  • pos_act(写法 A):调用 MuJoCo 内置 PD,参数就是 kp / kv
  • tor_act(写法 B):纯力矩通道,PD 留给 Python 手算后再写进来。
<mujoco model="single_pendulum">
<!-- 重力沿 z 轴向下; timestep=0.002 表示每 2 ms 推进一次物理仿真 -->
<option gravity="0 0 -9.81" timestep="0.002"/>

<worldbody>
<!-- body 原点放在世界坐标 (0,0,1); joint 未写 pos,默认就在这个原点 -->
<body name="link" pos="0 0 1">
<!-- hinge 只允许绕 y 轴转动; damping 是关节自身的物理阻尼,不是控制器的 Kd -->
<joint name="hinge" type="hinge" axis="0 1 0" damping="0.02"/>
<!-- fromto 是 body 局部坐标:胶囊中心线从 (0,0,0) 到 (0,0,-0.5),所以向下 0.5 m -->
<geom type="capsule" fromto="0 0 0 0 0 -0.5" size="0.04" mass="1"/>
</body>
</worldbody>

<actuator>
<!-- 写法 A: position 执行器。ctrl[0] 填目标角度 q_des;kp 对应 Kp,kv 对应 Kd 的速度阻尼项 -->
<position name="pos_act" joint="hinge" kp="20" kv="1" ctrlrange="-3.14 3.14"/>

<!-- 写法 B: motor 执行器。ctrl[1] 直接填关节力矩 tau,PD 公式由 Python 手算 -->
<motor name="tor_act" joint="hinge" ctrlrange="-5 5"/>
</actuator>
</mujoco>

对应的脚本 pd_single_joint.py 主循环就三件事:读 qpos / qvel → 算 PD → 写 ctrl,再交给 mj_step 推进物理。顶上的 use_motor 决定走哪一种写法,默认 True 即写法 B;这时要先把 pos_act 的增益清零,否则两个执行器会同时往关节上叠力矩,看到的就不是单一 PD 的响应。

from pathlib import Path
import time

import mujoco
import mujoco.viewer
import numpy as np

model = mujoco.MjModel.from_xml_path(str(Path(__file__).with_name("pendulum.xml")))
data = mujoco.MjData(model)

q_des = 0.8 # 目标角度(rad),约 45.8°; position 执行器和手写 PD 都跟踪这个目标
Kp, Kd = 20.0, 1.0 # 手写 PD 的比例/微分增益;刻意与 XML 里的 kp/kv 一致,方便对照

use_motor = True # True: 写 ctrl[1],用 motor 手搓 PD; False: 写 ctrl[0],用 position 执行器

if use_motor:
# MJCF 里同时定义了 pos_act 和 tor_act。
# 如果不关掉 pos_act,它会继续按 ctrl[0] 输出内置 PD 力矩,
# 这样就变成"内置 PD + 手写 PD"叠加,无法单独观察 motor 写法。
pos_act_id = mujoco.mj_name2id(model, mujoco.mjtObj.mjOBJ_ACTUATOR, "pos_act")
model.actuator_gainprm[pos_act_id, :] = 0.0 # 清掉 position 执行器的 kp 增益
model.actuator_biasprm[pos_act_id, :] = 0.0 # 清掉 position 执行器的 kv/偏置项

log = []
with mujoco.viewer.launch_passive(model, data) as viewer:
while viewer.is_running() and data.time < 8.0:
step_start = time.time()

q = data.qpos[0] # hinge 当前角度 q,对应 XML 里唯一的 joint
dq = data.qvel[0] # hinge 当前角速度 dq/dt

if use_motor:
# motor 模式:自己计算 tau = Kp(q_des - q) + Kd(0 - dq)
# 目标速度设为 0,表示只要求最终停在目标角度,不要求持续运动。
tau = Kp * (q_des - q) + Kd * (0.0 - dq)
data.ctrl[1] = np.clip(tau, -5.0, 5.0) # 写入 tor_act;clip 对应 XML 的 ctrlrange="-5 5"
else:
# position 模式:只给目标角度,MuJoCo 在内部用 kp/kv 自动算出关节力矩。
data.ctrl[0] = q_des # 写入 pos_act;范围受 ctrlrange="-3.14 3.14" 限制

mujoco.mj_step(model, data)
viewer.sync()
log.append((data.time, q, dq, data.ctrl.copy()))

# 让仿真按 wall-clock 走,viewer 看起来才是实时的
dt_left = model.opt.timestep - (time.time() - step_start)
if dt_left > 0:
time.sleep(dt_left)

把上面的 XML 保存为 pendulum.xml,把 Python 代码保存为 pd_single_joint.py,两个文件放在同一个目录下,然后运行:

macOS:

mjpython pd_single_joint.py

Linux / Windows:

python pd_single_joint.py

跑起来会弹出 viewer,杆子从竖直向下摆到 rad 附近稳住——这就是本章最核心的那条响应曲线。

单摆 PD 响应

,稳态略偏 ,差值就是 1.6.4 的稳态误差。

1.6.3 实验:增益响应

只看 1.6.2 里 那条单次响应, 仍然像两个调到不报错就行的旋钮。这一节固定 ,让 扫过欠阻尼 / 接近临界 / 过阻尼三个区段,把每个旋钮单独负责什么看清楚。

把下面脚本保存为 pd_experiments.py,和 pendulum.xml 放在同一个目录下。它不打开 viewer,直接跑 MuJoCo 物理并画出实验 1 / 实验 2 的曲线:

from pathlib import Path

import matplotlib.pyplot as plt
import mujoco
import numpy as np

q_des = 0.8


def make_model():
# 每组实验都重新加载一份 model,避免上一组仿真的状态或参数污染下一组。
model = mujoco.MjModel.from_xml_path(str(Path(__file__).with_name("pendulum.xml")))

# 这里统一使用 motor 通道手写 PD。
# 所以要关掉 XML 里同时存在的 position 执行器,否则会叠加两份控制力矩。
pos_act_id = mujoco.mj_name2id(model, mujoco.mjtObj.mjOBJ_ACTUATOR, "pos_act")
model.actuator_gainprm[pos_act_id, :] = 0.0 # 清掉 position 执行器的 kp
model.actuator_biasprm[pos_act_id, :] = 0.0 # 清掉 position 执行器的 kv/偏置项
return model


def run_pd(Kp, Kd, disturbance=False):
model = make_model()
data = mujoco.MjData(model)
ts, qs = [], [] # 只记录时间和角度,用于画响应曲线

while data.time < 8.0:
q = data.qpos[0] # 当前关节角度
dq = data.qvel[0] # 当前关节角速度

# 手写 PD:目标速度设为 0,所以 D 项是 Kd * (0 - dq)。
tau = Kp * (q_des - q) + Kd * (0.0 - dq)

# 写入 motor 执行器的 ctrl[1];clip 对应 XML 里的 ctrlrange="-5 5"。
data.ctrl[1] = np.clip(tau, -5.0, 5.0)

# 实验 2 使用:3 秒后施加恒定外扰,观察 PD 是否能消掉稳态误差。
data.qfrc_applied[0] = 2.0 if disturbance and data.time > 3.0 else 0.0

mujoco.mj_step(model, data)
ts.append(data.time)
qs.append(data.qpos[0])

return np.array(ts), np.array(qs)


plt.figure(figsize=(8, 4))
# 实验 1:固定 Kp,只改变 Kd,看欠阻尼 / 临界附近 / 过阻尼三种响应。
for Kd, label in [(0.5, "A: Kd=0.5"), (12.0, "B: Kd=12"), (40.0, "C: Kd=40")]:
t, q = run_pd(Kp=40.0, Kd=Kd)
plt.plot(t, q, label=label)
plt.axhline(q_des, linestyle="--", color="black", label="target")
plt.xlabel("time (s)")
plt.ylabel("q (rad)")
plt.legend()
plt.grid(True)
plt.tight_layout()
plt.savefig("pd_kd_sweep.png", dpi=200)

plt.figure(figsize=(8, 4))
# 实验 2:加入恒定外扰,对比纯 P 和 PD 的稳态误差。
for Kd, label in [(0.0, "P only"), (1.0, "PD")]:
t, q = run_pd(Kp=20.0, Kd=Kd, disturbance=True)
plt.plot(t, q, label=label)
plt.axhline(q_des, linestyle="--", color="black", label="target")
plt.axvline(3.0, linestyle=":", color="gray", label="disturbance")
plt.xlabel("time (s)")
plt.ylabel("q (rad)")
plt.legend()
plt.grid(True)
plt.tight_layout()
plt.savefig("pd_disturbance_error.png", dpi=200)

运行:

python pd_experiments.py

实验 1 用三组参数:

预期 现象
A 欠阻尼400.5≈ 0.04反复冲过目标来回晃
B 临界附近4012≈ 0.95最快到达且基本不过冲
C 过阻尼4040≈ 3.16单调爬升,但慢

(按 估算 ,需要更准就用 MuJoCo 的 mj_fullM 读真实惯量。)

实验 1:固定 Kp=40,只改变 Kd 时的单摆响应曲线
实验 1:固定 Kp=40,只改变 Kd 时的单摆响应曲线

把三条曲线放在一起看,会更容易看出几个现象:

  1. 决定回正力矩的量级 要先大到能抵消重力矩 ,单摆才能到达 附近;即便如此稳态仍会偏一截,这个偏差正是 1.6.4 要拆解的稳态误差,调 不解决。
  2. 是控制器主动出的阻尼,跟 MJCF 里的 damping 不是同一件事。后者是关节本身的物理阻尼,写在 XML 里、和控制器无关;想干净地观察 的作用,就把 damping 设小一点,避免两份阻尼混在一起。
  3. 太大会让仿真先于真机崩 加到某个值之后曲线出现高频噪声甚至发散,这是 timestep 跟不上 的信号,不是 PD 公式错了;把 timestep 调小、或把 减小,都能压下去。

1.6.4 实验:扰动误差

实验 2 用同一个 pd_experiments.py,只是在第 3 秒后给关节一个持续外力矩:

data.qfrc_applied[0] = 2.0 if disturbance and data.time > 3.0 else 0.0
实验 2:3 秒后加入恒定外扰,P 和 PD 都会留下稳态误差
实验 2:3 秒后加入恒定外扰,P 和 PD 都会留下稳态误差

我们会看到两种明显不同的行为:

  • 纯 P 控制():关节稳在一个偏离 的新位置上,差的那一截正好是 。这就是"稳态误差"。
  • PD 控制:在 P 的基础上抖动更小地到达那个偏移位置,但稳态误差依然存在——因为误差一恒定,微分项就为 0,不产生额外的修正力。

想把这个偏差也消掉,就要引入积分项 ,PD 升级成 PID。PID 是下一层故事,本章把这个"为什么 PD 吃不掉恒定扰动"亲手看一眼就够了。

小结

本章沿「执行器 → 控制系统 → Bang-Bang → PID → PD → MuJoCo 实现」走了一遍单关节最底层的反馈控制。几条值得带走的结论:

  • 硬件决定了 PD 真正控的那个二阶系统。电机选型时看的是扭矩 / 速度 / 精度,但 PD 调参时真正起作用的是经齿轮箱放大的反射惯量 。准直驱(QDD) 与高减速比(谐波) 两条路线在 PD 表现上差异极大——sim-to-real 对不上,绝大多数出在这组数字而不是公式本身。

  • Bang-Bang → PID → PD 是连续松绑的同一条链。Bang-Bang 只看误差符号、输出 两档,在机器人关节上必然陷入极限环;P 把开关换成正比于误差的连续输出,留下稳态误差;I 累积过去误差吃掉稳态误差;D 预判误差变化、提前反向出力。三项各管时间的一个维度——当前、过去、未来。

  • 机器人里实际用的是 PD 而非 PID,原因有三:积分饱和在物理世界里会演变成"卡住后突然甩出"的安全风险;PD 与虚拟弹簧-阻尼器严格等效,让阻抗控制 / 柔顺交互天然成立;机械臂主要的稳态误差来源是重力,可以靠动力学前馈精确消除,不必让 I 盲目累加。

  • PD 调参的骨架是把闭环看成二阶振子 决定响应快慢, 决定阻尼。先按目标响应选 ,再按 算出 ,就能得到一个既不晃又不慢的响应;真机上还要叠加摩擦、传动间隙、采样延迟等修正。

  • MuJoCo 里 position 执行器内部就是一条 PD(kp / kv),想看清 P 与 D 各自的贡献就用 motor + 自写 PD。timestep 是物理步长而非控制周期,要对齐真机控制频率,得让 Python 循环每 timestep 更新一次 ctrl

到这里,我们已经能让一个单自由度关节稳定到达任意目标角度——这是后面所有内容的地基。第 5 章会把同一套 PD 同时套到四足机器人的全部关节上去拼出 trot 步态;再之后的 RL 步态、LLM 控制,本质上都在找一个更复杂的 ,而最内层那条 PD 通常仍然存在。

思考

  1. 实验 1 里 A 组取 ,响应曲线剧烈振荡。如果想保留 、把响应压成接近临界阻尼, 大概要取多少?(提示:先用 估单摆惯量,再代 。)

  2. 一台准直驱(QDD)四足机器人减速比 ,另一台协作机械臂用谐波减速器 ,两者电机本体惯量相同。如果把同一组 直接移植过去,响应会发生什么变化?为什么?

  3. 1.5.2 节把 称为"阻尼系数",1.6.3 节又强调" 不是 MJCF 里的 damping"。这两个"阻尼"在物理上有什么区别?如果只在 MJCF 里把 damping 调大,能不能替代控制器里的

  4. 既然计算力矩控制可以用动力学前馈精确消掉重力带来的稳态误差,是不是任何机器人都可以彻底放弃 I 项?在哪些场景下我们仍然必须保留 I?

  5. position 执行器和 motor + 自写 PD 在数学上完全等价,但调试体验差别很大。如果我们想搞清某次过冲到底是 太大、 太小,还是力矩饱和触发的,我们会优先选哪一种写法?为什么?

动手任务

到这里我们已经能让一个单关节 PD 稳定到达任意目标。组队 Lab 1 把同一个 PD 接到 Pupper HFE 关节上换到频域看一遍——用一系列正弦输入扫频,在 Bode 图上读出 1.5 节那对 ,再亲眼看 1.6.5 节"力矩饱和把高频压平"是怎么发生的。

Lab 1 teaser:HFE 跟踪 0.3 Hz 正弦

HFE 关节跟踪 0.3 Hz 正弦目标:左侧是 Pupper 单腿响应,右侧是同一组数据实时打到 Bode 图上的两个点(一组幅值、一组相位)。低频 、相位 ;扫到高频段我们会看到增益下降、相位往 走——本章 1.5 那对 在频域留下的指纹。

要做的四件事:

  • 把 PD 接到 shared/models/leg.xml 的 HFE 上,先用常值 把腿稳住
  • mj_fullM 读反射惯量 ,按 自动算
  • Hz 七点扫频,记录稳态幅值和相位差,画 magnitude / phase 双轴 Bode 图
  • dB 带宽——高频段曲线偏离一阶低通形状的部分,对应 1.6.3 里的哪条坑?

完整 starter / 测试 / 交付清单见 exercises/lab_1_pid_bode/

参考资料