Impedance Controller Design and Robustness Analysis

Jan 3, 2024 | Tech Robotics

Motivation

Impedance controllers are commonly employed to control robotic systems. They typically transform the controlled system dynamics into a standard second order mass-spring-damper system, in which the proportional and derivative control gains correspond to stiffness and damping. Such close analogy to physical systems makes it easy to design, interpret, and evaluate the control gains.

There are different ways to design impedance controllers. Some of them are more robust to model uncertainties than others. This post summarizes the classic impedance controller design and its drawback, then compare it with a unique method proposed in 2004@Albu-Schaffer .

Nomenclature

In addition to nomenclature used in Fundamentals of Dynamics and Control of Flexible Joint Robots and Operational Space Framework, Hybrid Motion-Force Control:

  • $\omega, \dot{\omega}, \ddot{\omega}$ - generalized eigen coordinate position, velocity, acceleration
  • $K$ - stiffness matrix in system's original coordinates
  • $D$ - damping matrix in system's original coordinates
  • $K_{\omega}$ - stiffness matrix in system's generalized eigen coordinates
  • $D_{\omega}$ - damping matrix in system's generalized eigen coordinates
  • $Q$ - square nonsingular matrix that transforms a mechanical system from its original coordinates into its generalized eigen coordinates, such as $\omega = Q^T q$

In addition, generalized eigen coordinates are also referred to as modal coordinates. As it will become clear later in the post.

The Classic Impedance Controller

The robot dynamics in its joint space is given by $$ M\ddot{q} + c + g = \tau \label{eq:dynamics} $$ If the torque is designed to be $$ \tau = M \textcolor{blue}{u^*} + c + g \label{eq:js-law} $$ $$ \textcolor{blue}{ u^* = -K(q - q_d) - D(\dot{q} - \dot{q}_d) + \ddot{q}_d \label{eq:js-u} } $$ the system dynamics would become a standard unit mass spring damper system $$ \ddot{\tilde{q}} + D \dot{\tilde{q}} + K \tilde{q}= 0 $$ with $K$ and $D$ correspond to stiffness and damping.

Control Effort Analysis and Source of Uncertainties

Below are some critical observations:

  • in the classic impedance controller given in \eqref{eq:js-law} and \eqref{eq:js-u}, the entire control effort is mapped by the corresponding mass matrix $M$,
  • however, the mass matrix $M$ typically cannot be accurately estimated,
  • when $M$ is a bad estimation, especially with bad estimation on the off-diagonal terms (which introduces undesired coupling effect), the controlled system's dynamics will not resemble a second order system and hence the performance will be negatively affected.

As a result, it would be ideal if one can design a controller that renders the system dynamics a standard mass-spring-damper system without having to map the control effort by a possibly inaccurate estimation of $M$.

Generalized Eigen Coordinate Impedance Controller

To address the issued mentioned in the previous section, 2004@Albu-Schaffer proposed the following impedance controller design. Given a symmetric positive definite matrix $ M \in \mathbb{R}^{n \times n}$ in \eqref{eq:dynamics} and a symmetric matrix $K_{\omega} \in \mathbb{R}^{n \times n} $, there exists $Q \in \mathbb{R}^{n \times n}$ such that $M=QQ^T$ and $K=QK_{\omega}Q^T$ for some diagonal matrix $K_{\omega} \in \mathbb{R}^{n \times n}$.

Such a decomposition is commonly seen in structure vibration analysis, and is referred to as modal coordinate decomposition, as discussed in MIT, Engineering Dynamics, Modal Analysis. And the matrix $Q$ maps system's original coordinates to its modal coordinates, i.e., its generalized eigen coordinates, $$ Q^T q = \omega $$

When applying to impedance controller design, what it is saying is that, if one designs a controller in the form of $$ M\ddot{q} + c + g = \tau = \textcolor{red}{\tau^*} + c + g \label{eq:eigen-control} $$ it will render the system into $$ M\ddot{q} = \textcolor{red}{\tau^*} $$ and if one chooses $$ \textcolor{red}{\tau^*} = \textcolor{red}{-K(q - q_d)} - 2QD_{\omega}K_{\omega}^{1/2}Q^T(\dot{q} - \dot{q}_d) + \textcolor{red}{\ddot{q}_d} \label{eq:eigen-control-effort} $$ with a design parameter $D_{\omega} \in \mathbb{R}^{n \times n}$ representing a damping matrix, the system dynamics becomes $$ \underbrace{QQ^T}_{M} \ddot{\tilde{q}} + 2QD_{\omega}K_\omega^{1/2}Q^T\dot{\tilde{q}} + \underbrace{QK_{\omega}Q^T}_{K} \tilde{q} = 0 \label{eq:modal-dynamics} $$ as $Q^T q = \omega$ and the $Q$ matrix on the left of each term can be canceled by left multiplying $Q^{-1}$, it reveals that the controlled system is effectively a decoupled unit-mass spring damper system in the $\omega$ modal coordinates $$ \ddot{\tilde{\omega}} + 2D_{\omega}K_{\omega}^{1/2}\dot{\tilde{\omega}} + K_{\omega}\tilde{\omega} = 0 $$

Analysis and Comparison

One can observer from control law given in \eqref{eq:eigen-control} and \eqref{eq:eigen-control-effort} that:

  • the typically dominant P-term, and the acceleration feedforward term, are not mapped by the system's mass matrix,
  • only the damping term is actively affected by the system's mass matrix through its decomposition matrix $Q$, and it can be controlled by choosing a proper $D_{\omega}$,
  • the system dynamics is a standard second order in its modal coordinates with designed stiffness and damping.

These are the advantages of the generalized eigen coordinate impedance controller.

However, since this controller renders the system into a unit-mass spring damper system in its modal coordinates. The controller's convergence trajectory is typically not a straight line in its original space. Because there exists a transformation between the original coordinates and the modal coordinates that does not preserve the exact geometric shape of the transformed quantities.

But this drawback can usually be mitigated by high quality trajectories that are C2 continuous or above, and divide a long trajectory into many infinitesimally small pieces, in which the deviation in each small piece is negligible.

Generalization to Operational Space

The modal coordinates impedance controller design can easily generalize to the operational space. Given the operational space dynamics $$ J^T \Bigl\{ \Lambda \ddot{x} + \mu + \rho = F \Bigl\} $$ and a stiffness matrix $K$, the following still holds $$ \Lambda=QQ^T $$ $$ K=QK_{\omega}Q^T $$ with some different $Q$ matrix. As before, one can design a controller $$ F = \textcolor{red}{F^*} + \mu + \rho $$ $$ \textcolor{red}{F^*} = \textcolor{red}{-K(x - x_d)} - 2QD_{\omega}K_{\omega}^{1/2}Q^T(\dot{x} - \dot{x}_d) + \textcolor{red}{\ddot{x}_d} \label{eq:control-force} $$ which, again, renders the operational space dynamics into a decoupled unit-mass spring damper system $$ \ddot{\tilde{\omega}} + 2D_{\omega}K_{\omega}^{1/2}\dot{\tilde{\omega}} + K_{\omega}\tilde{\omega} = 0 $$ in some different $\omega$ modal coordinates.

And notice that for the final control torque sent to the robot $$ \tau = J^T (\textcolor{red}{F^*} + \mu + \rho) $$ the P-term and acceleration feedforward in \eqref{eq:control-force} are only mapped by the robot Jacobian, not the operational space mass matrix $\Lambda$, as oppose to the classic operational impedance controller where all feedback terms are mapped by the operational space mass matrix $$ \tau = J^T (\Lambda \textcolor{blue}{F^*} + \mu + \rho) $$ $$ \textcolor{blue}{ F^* = -K(x - x_d) - K(\dot{x} - \dot{x}_d) + \ddot{x}_d }$$ Hence, the modal coordinate impedance controller preserves its advantages in the operational space as well.

Final Notes

In some cases, in both joint space and operational spaces, it happens that $M$ or $\Lambda$ could become ill-conditioned, especially in operation space when robot is in singularities, not very likely in joint space. When it happens, the modal coordinate impedance controller's damping term $$ \mathcal{D} = 2QD_{\omega}K_{\omega}^{1/2}Q^T $$ could become infinitely large, causing controller instability.

There are two ways to handle it, the first one is to use some damped Singular Value Decomposition (SVD) to process the $Q$ matrix before computing $K_\omega$ and $\mathcal{D}$. The other one is to use directly apply the damped SVD to process $\mathcal{D}$.

Using damped SVD to handle singularities is a rather common and general technique, it will be discussed in detail in a separate post.