阻抗&导纳控制理解

书籍《Modern Robotics - Mechanics , Planning, and Control》中关于阻抗控制和导纳控制的部分:







下面结合上边的内容谈一谈我对导纳控制的理解。

1、质量-弹簧-阻尼

首先,不论是阻抗控制,还是导纳控制,他们同根同源,都是基于质量-弹簧-阻尼 动力学模型而产生的。下图所示是一个单自由度质量-弹簧-阻尼 虚拟环境:

对其进行受力分析:

根据牛顿第二定律,有 m x ¨ = f − k x − b x ˙ , m \ddot x = f - kx - b \dot x, mx¨=f−kx−bx˙,表明物块的运动状态(位移 x x x、速度 x ˙ \dot x x˙、加速度 x ¨ \ddot x x¨)和 其所受外力 f f f 之间满足: m x ¨ + b x ˙ + k x = f , m\ddot x + b \dot x + kx = f, mx¨+bx˙+kx=f,对该动力学方程左右两侧进行拉普拉斯变换,得到 ( m s 2 + b s + k ) X ( s ) = F ( s ) . (ms^2+bs+k)X(s) = F(s). (ms2+bs+k)X(s)=F(s).阻抗 被定义为位置扰动到力的传递函数 Z ( s ) = F ( s ) / X ( s ) Z(s) = F(s)/X(s) Z(s)=F(s)/X(s)(输入位置、输出力),所以阻抗是频率相关的,低频响应由弹簧决定,高频响应由质量决定。
导纳 被定义为力扰动到位置的传递函数,是阻抗的倒数, Y ( s ) = X ( s ) / F ( s ) Y(s) = X(s)/F(s) Y(s)=X(s)/F(s)(输入力,输出位置)。

2、阻抗/导纳的设计初衷---实现柔顺

不论是阻抗还是导纳控制器,都是为了实现柔顺控制。

传统的误差驱动的位置控制器,例如 P D PD PD 控制器、 P I D PID PID 控制器...就是为了消除外部扰动带来的跟踪偏差,然而外力的引入势必会导致偏差的增大,两者相互对抗,机器人就像一个钢铁直男宁折不弯;

而基于阻抗/导纳控制器的柔顺体现在,当机器人受到外力干扰,机器人不会像在位置控制器模式下一样和外力作用硬碰硬,而是会顺应外力运动,当外力撤销,机器人便会恢复到原始的运动状态,主打一个接化发

重点在于,机器人顺应外力运动的原则就是:呈现弹簧-质量-阻尼的动力学特性。

回到公式,阻抗/导纳控制的目标是实现任务空间行为 M d x ¨ + B d x ˙ + K d x = f e x t , M_d \ddot x + B_d \dot x + K_d x = f_{ext}, Mdx¨+Bdx˙+Kdx=fext,其中 x ∈ R n x \in \mathbb R^n x∈Rn 是最小坐标集中的任务空间配置,例如 x ∈ R 3 x \in \mathbb R^3 x∈R3; M d M_d Md、 B d B_d Bd 和 K d K_d Kd 是期望的正定虚拟质量、阻尼和刚度矩阵, f e x t f_{ext} fext 是施加到机器人上的力,可能是由用户施加的,还可以在机器人的受控运动中用相对于参考值 的小位移 e ¨ \ddot e e¨、 e ˙ \dot e e˙ 和 e e e 替换 x ¨ \ddot x x¨、 x ˙ \dot x x˙ 和 x x x ,即 M d e ¨ + B d e ˙ + K d e = f e x t , M_d \ddot e + B_d \dot e + K_d e = f_{ext}, Mde¨+Bde˙+Kde=fext,其中, e = x − x 0 e = x-x_0 e=x−x0, x x x 是机器人位置, x 0 x_0 x0 是期望平衡轨迹 (desired equilibrium trajectory),举个例子,假设机器人末端在笛卡尔空间跟踪一个椭圆轨迹,那么这个椭圆轨迹就是这里提到的期望平衡轨迹,此时它是随时间变化的;再举个例子,假设机器人末端在笛卡尔空间保持不动,那么机器人保持不动的这个位置就是这里提到的期望平衡轨迹,准确的说,其实是一个期望平衡点(desired equilibrium point),此时它不随时间变化。但是,x 0 x_0 x0 不是指机器人的初始位置!

3、什么是阻抗控制和导纳控制?

下面还是以一个与环境交互的单自由度质量块系统为例,阐述阻抗控制和导纳控制。

假设质量块的质量为 m m m, x x x 是质量块的位移, F F F 是控制力, F e x t F_{ext} Fext 为环境作用在质量块上的外力,质量块的运动方程表达为:
m x ¨ = F + F e x t (1) \begin{aligned} m \ddot x = F + F_{ext} \\ \end{aligned}\tag{1} mx¨=F+Fext(1)导纳和阻抗控制的控制目标都是设计控制力 F F F 使外部力 F e x t F_{ext} Fext 和 e = ( x − x 0 ) e = (x-x_0) e=(x−x0)之间建立质量-弹簧-阻尼动力学关系: M d e ¨ + D d e ˙ + K d e = F e x t (2) \begin{aligned} M_d \ddot e + D_d \dot e + K_d e = F_{ext} \\ \end{aligned}\tag{2} Mde¨+Dde˙+Kde=Fext(2)

3.1 阻抗控制(Impedance control)

在阻抗控制中,控制器是一个机械阻抗,被控对象被当作导纳对待,如下图所示:

结合公式(1)和公式(2),推导得到阻抗控制律: F = ( m M d − 1 ) F e x t + m x ¨ 0 − m M d ( D d e ˙ + K d e ) (3) \begin{aligned} F = (\frac{m}{M_d}-1)F_{ext} + m \ddot x_0 - \frac{m}{M_d}(D_d \dot e + K_d e) \\ \end{aligned}\tag{3} F=(Mdm−1)Fext+mx¨0−Mdm(Dde˙+Kde)(3)

3.2 导纳控制(Admittance control)

在导纳控制中,受控对象基于位置控制,而不再像阻抗控制器那样基于力控制,如下图所示:

其中,位置控制器可采用 P D PD PD 控制器实现: F = k p ( x d − x ) − k d x ˙ (4) \begin{aligned} F = k_p(x_d - x) - k_d \dot x \\ \end{aligned}\tag{4} F=kp(xd−x)−kdx˙(4)将公式(4)带入公式(1),得到
m x ¨ + k d x ˙ + k p ( x − x d ) = F e x t (5) \begin{aligned} m \ddot x + k_d \dot x + k_p(x-x_d) = F_{ext} \\ \end{aligned}\tag{5} mx¨+kdx˙+kp(x−xd)=Fext(5)将 x x x 替换为 x d x_d xd 重写公式(2),得到
M d ( x ¨ d − x ¨ 0 ) + D d ( x ˙ d − x ˙ 0 ) + K d ( x d − x 0 ) = F e x t (6) \begin{aligned} M_d (\ddot x_d - \ddot x_0) + D_d (\dot x_d-\dot x_0) + K_d (x_d - x_0) = F_{ext} \\ \end{aligned}\tag{6} Md(x¨d−x¨0)+Dd(x˙d−x˙0)+Kd(xd−x0)=Fext(6)公式(5)(6) 便是导纳控制系统的完整动力学。

4、导纳控制的实际实现

在导纳控制算法中,用户/环境施加的外力 f e x t f_{ext} fext 由末端 F/T 传感器测量并转换到机器人基座标系下而获得,机器人以满足方程式 M d x ¨ + B d x ˙ + K d x = f e x t M_d \ddot x + B_d \dot x + K_d x = f_{ext} Mdx¨+Bdx˙+Kdx=fext 的末端执行器加速度响应,一种简单的方法是根据下式计算期望的末端执行器加速度 x ¨ d \ddot x_d x¨d: M d x ¨ d + B d x ˙ + K d x = f e x t (7) \begin{aligned} M_d \ddot x_d + B_d \dot x + K_d x = f_{ext} \\ \end{aligned}\tag{7} Mdx¨d+Bdx˙+Kdx=fext(7)其中 ( x , x ˙ ) (x,\dot x) (x,x˙) 是当前状态。求解,我们得到 x ¨ d = M d − 1 ( f e x t − B d x ˙ − K d x ) (8) \begin{aligned} \ddot x_d = M_d^{-1}(f_{ext} - B_d \dot x - K_d x) \\ \end{aligned}\tag{8} x¨d=Md−1(fext−Bdx˙−Kdx)(8)说白了,就是为了使机器人满足质量-弹簧-阻尼 二阶动力学,根据机器人当前控制周期的状态 ( x , x ˙ ) (x,\dot x) (x,x˙) 和外部力 f e x t f_{ext} fext,计算得到满足该动力学的加速度值,而后以计算出来的加速度值进行积分,得到下一控制周期的速度指令 (适用于机器人底层是速度控制器) ;如果对得到的速度指令再进行积分,就会得到下一控制周期的位置指令 (适用于机器人底层是位置控制器) 。

在实际应用场景中,不论是定点导纳控制,还是在轨迹跟踪任务中加入导纳柔顺控制策略,这些机器人受控运动都是具有预定义的参考轨迹 (期望平衡轨迹) 的,因此,公式 (9) 形式描述的阻抗模型更为实用: M d e ¨ + D d e ˙ + K d e = F e x t (9) \begin{aligned} M_d \ddot e + D_d \dot e + K_d e = F_{ext} \\ \end{aligned}\tag{9} Mde¨+Dde˙+Kde=Fext(9)

  • M d M_d Md:期望惯性系数对角矩阵;
  • D d D_d Dd:期望阻尼系数对角矩阵;
  • K d K_d Kd:期望刚度系数对角矩阵;
  • F e x t F_{ext} Fext:机器人基坐标系 下的环境力。我们要知道,从末端 F/T 传感器获取的测量值是在传感器坐标系下的表示,通常传感器坐标系和末端法兰坐标系保持一致,因此,将传感器坐标系下获取的测量值左乘旋转矩阵即可获得外部环境力在机器人基坐标系下的直观对应;
  • e = x − x 0 = [ Δ v , Δ w ] e = x-x_0=[\Delta v,\Delta w] e=x−x0=[Δv,Δw] 为机器人基坐标系下描述的机器人实际位姿 x x x 与期望平衡位姿 x 0 x_0 x0 之差。其中,位置偏差 = 当前实际位置 - 期望平衡位置,可以直接相减;但是姿态不可以直接相减,描述姿态的表达方式有多种:旋转矩阵、欧拉角、四元数、等效轴角等,旋转矩阵形式的姿态偏差求法: R e = R R 0 T R_e = R R_0^T Re=RR0T,相当于:姿态偏差 = 当前实际姿态 - 期望平衡姿态,另外程序中一般采用 [ 3 , 1 ] [3,1] [3,1] 向量描述姿态,所以要将其转换为等效转轴描述的姿态偏差 Δ w \Delta w Δw (韩冰老师说:传感器采集的扭矩相当于等效转轴描述);
cpp 复制代码
            // compute error to desired equilibrium pose
            pos_error.head(3) << curr_position_ - desired_position_;																						//  位置偏差,直接相减
            if (desired_pose_orientation_.coeffs().dot(curr_orientation_.coeffs()) < 0.0) {												// 四元数形式确认符号
                curr_orientation_.coeffs() << -curr_orientation_.coeffs();
            }
            // "difference" quaternion																																						// 姿态偏差求解为四元数形式
            Eigen::Quaterniond quat_rot_err (curr_orientation_ * desired_pose_orientation_.inverse());
            if(quat_rot_err.coeffs().norm() > 1e-3)
            {
                quat_rot_err.coeffs() << quat_rot_err.coeffs()/quat_rot_err.coeffs().norm();
            }
            Eigen::AngleAxisd err_arm_des_orient(quat_rot_err);                                 																// 四元数转轴角
            pos_error.tail(3) << err_arm_des_orient.axis() * err_arm_des_orient.angle();        										// 从轴角获取 3*1 向量
  • e ˙ = x ˙ − x ˙ 0 \dot e = \dot x - \dot x_0 e˙=x˙−x˙0 和 e ¨ = x ¨ − x ¨ 0 \ddot e = \ddot x - \ddot x_0 e¨=x¨−x¨0 为 e e e 的一阶导数和二阶导数;

参照公式 (7)(8)的导纳控制实现理念,将公式 (9) 所示的阻抗模型改写为如下表达形式:
e ¨ t = M d − 1 ( F e x t − D d e ˙ t + K d e t ) (10) \begin{aligned} \ddot e_t = M_d^{-1}(F_{ext} - D_d \dot e_t + K_d e_t) \\ \end{aligned}\tag{10} e¨t=Md−1(Fext−Dde˙t+Kdet)(10)积分
e ˙ t + 1 = e ˙ t + e ¨ t Δ t (11) \begin{aligned} \dot e_{t+1} = \dot e_t + \ddot e_t \Delta t \\ \end{aligned}\tag{11} e˙t+1=e˙t+e¨tΔt(11)再积分
e t + 1 = e t + e ˙ t + 1 Δ t (12) \begin{aligned} e_{t+1} = e_t + \dot e_{t+1} \Delta t \\ \end{aligned}\tag{12} et+1=et+e˙t+1Δt(12)

如果机器人底层控制器是速度接口,则下一周期速度控制指令
x ˙ d t + 1 = e ˙ t + 1 + x ˙ 0 t + 1 (13) \begin{aligned} \dot x_d^{t+1} = \dot e_{t+1} + \dot x_0^{t+1} \\ \end{aligned}\tag{13} x˙dt+1=e˙t+1+x˙0t+1(13)如果机器人底层控制器是位置接口,则下一周期的位置控制指令:
x d t + 1 = e t + 1 + x 0 t + 1 (14) \begin{aligned} x_d^{t+1} = e_{t+1} + x_0^{t+1} \\ \end{aligned}\tag{14} xdt+1=et+1+x0t+1(14)

举例来说,对于定点导纳控制,机器人的期望平衡轨迹实际上只有位姿,由于机器人保持不动,速度和加速度都为零,公式 (10)~(14) 就简化为:
x ¨ d t = M d − 1 ( F e x t − D d x ˙ t + K d ( x t − x 0 t ) ) x ˙ d t + 1 = x ˙ t + x ¨ d t Δ t x d t + 1 = x t + x ˙ d t + 1 Δ t \ddot x_d^{t} = M_d^{-1}(F_{ext} - D_d \dot x_t + K_d (x_t-x_0^t)) \\ \dot x_d^{t+1} = \dot x_t + \ddot x_d^t \Delta t \\ x_d^{t+1} = x_t + \dot x_d^{t+1} \Delta t x¨dt=Md−1(Fext−Ddx˙t+Kd(xt−x0t))x˙dt+1=x˙t+x¨dtΔtxdt+1=xt+x˙dt+1Δt

但是在以上积分求解过程中应该注意,公式 (11) 由 e ¨ t \ddot e_t e¨t 到 e ˙ t + 1 \dot e_{t+1} e˙t+1 的位置和姿态积分直接叠加即可;但是公式 (12) 由 e ˙ t + 1 \dot e_{t+1} e˙t+1 到 e t + 1 e_{t+1} et+1 的位置积分可以直接叠加,姿态积分不可以直接叠加,必须转换成姿态旋转矩阵描述后进行旋转矩阵姿态运算叠加,叠加表达式: R t + 1 = Δ R R t R_{t+1} = \Delta R R_t Rt+1=ΔRRt,其中, Δ R \Delta R ΔR 由 e ˙ t + 1 Δ t \dot e_{t+1} \Delta t e˙t+1Δt 的等效转轴姿态描述转换而来,并且矩阵乘法不满足交换律,注意先后顺序。公式 (14)的姿态叠加处理方式相同。所以注意,姿态求解过程中涉及到的姿态偏差求解和姿态叠加求解,是能否正确实现姿态导纳控制的关键。

5、总结

Github 上找到的一些开源代码是仿真或者是基于实际机械臂的,但都是基于速度控制接口的机械臂,导纳控制器直接计算得到速度指令,供底层速度控制器去跟踪,鲜有看到导纳控制器计算得到位置指令,让底层位置控制器去跟踪,虽然没有什么理论深度,但是涉及到笛卡尔空间下位置和姿态一共6个自由度的时候,还是有很多要注意的点的,特此在此总结。

综上所述,阻抗控制和导纳控制是两种实现弹簧-质量-阻尼动力学的方式,根据实际条件,实际应用场景的不同,应该选择合适的方式实现所需要的柔顺特性。

参考资源

CSDN博客:【机器人基础】阻抗/导纳控制深度解析
知乎帖_韩冰老师:基于六维力传感器机器人导纳控制
知乎帖_基于位置的阻抗控制------导纳控制
知乎帖_段晋军老师:阻抗控制和导纳控制在机器人中的应用

参考论文:2010 ICRA"Unified Impedance and Admittance Control"

相关推荐
kuan_li_lyg1 年前
MATLAB - 机器人任务空间运动模型
开发语言·matlab·机器人·自动驾驶·ros·机器人控制·任务空间控制
kuan_li_lyg1 年前
MATLAB - 卫星自旋的模型参考自适应控制(MRAC)
matlab·机器人·自动驾驶·ros·机器人控制·模型参考自适应控制·自适应控制
kuan_li_lyg1 年前
MATLAB - 使用运动学 DH 参数构建机械臂
开发语言·matlab·机器人·自动驾驶·ros·机器人控制·机器人建模
kuan_li_lyg1 年前
MATLAB - 计算关节扭矩以平衡端点力和力矩
开发语言·matlab·机器人·自动驾驶·ros·机器人控制·机器人动力学
kuan_li_lyg1 年前
OCS2 入门教程(五)- 从 URDF 到 OCP、配置求解器、MPC - Net
人工智能·机器人·自动驾驶·ros·四足机器人·机器人控制·最优控制
kuan_li_lyg1 年前
OCS2 入门教程(四)- 机器人示例
人工智能·机器人·自动驾驶·ros·机器人控制·足式机器人·移动机械臂
kuan_li_lyg1 年前
MATLAB - 机器人逆运动学设计器(Inverse Kinematics Designer APP)
开发语言·matlab·机器人·自动驾驶·ros·机器人控制·逆运动学
kuan_li_lyg1 年前
MATLAB - Gazebo 仿真环境
matlab·机器人·自动驾驶·ros·gazebo·机器人控制·机器人仿真
kuan_li_lyg1 年前
Crocoddyl: 多接触最优控制的高效多功能框架
机器人·自动驾驶·ros·机器人控制·人形机器人·最优控制·crocoddyl