User Tools

Site Tools


Upload failed. Maybe wrong permissions?
adrl:education:completed_projects:sven2013f

<latex>{\fontsize{16pt}\selectfont \textbf{Optimization of the Low-Level Torque Controller of the Quadruped Robot HyQ}} </latex>

<latex>{\fontsize{12pt}\selectfont \textbf{[Sven Hubacher]}} </latex>
<latex>{\fontsize{10pt}\selectfont \textit{[Master's Thesis]}} </latex>

<latex> {\fontsize{13pt}\selectfont \textbf{Abstract} </latex>
The hydraulica quadruped robot HyQ at the ETH Zurich is a four legged robot capable of versatile, robust and dynamic maneuvers. The robot is fully position and torque controlled, the latter enabling the use of many control laws that produce torque commands as outputs. To allow best performance of these control laws, a perfect torque source is desired. Currently a nonlinear partial feedback linearization controller 1) with fixed gains is used for torque tracking in the hydraulic actuation system. Changing load conditions, e.g. when the robot is walking, pose difficulties for this fixed gain low-level controller not being able to follow the torque command satisfactory. Therefore, this work presents an adaptive control framework to cope with changing system dynamics by recursively estimating the current system dynamics and updating the low-level controller when needed. The hydraulic cylinder dynamics are first studied and analysed. Then an adaptive control framework is proposed and its effectiveness is shown in simulation. Controller and estimator are implemented on a real-time hydraulic cylinder test set-up. Experimental results assess the performance of the estimator. The controller is verified for different load conditions and the possible gain in performance is pointed out when using the proposed adaptive control framework.


<latex> {\fontsize{13pt}\selectfont \textbf{Introduction} </latex>
The robot HyQ 2) 3) is a hydraulically quadruped robot capable of versatile, robust and dynamic maneuvers 4) developed at the Istituto Italiano di Tecnologia (IIT) in Genoa, Italy. The robot's versatility, such as reflex generation 5) and trotting assisted by stereo-vision 6), has been shown in many publications. The robot is both position and torque controlled, the latter enabling the use of many control concepts that produce torque outputs, such as impedance control 7). Force or torque commands are also used by inverse dynamics and for the robot's balance where the leg contact points are not moved, but forces are introduced to keep the robot in balance. The interaction with the environment occurs via forces, thus force controlled robots allow for compliant behavior 8).

All these mentioned concepts depend on the performance of the low-level torque controller. A better-performing low-level controller maximizes the effectiveness of these higher-level control concepts. Therefore, a perfect torque source is desired, that is, a low-level controller able to track a torque reference in any circumstance.

However, providing such a perfect torque source is a difficult task and cannot always 9) be fulfilled, especially when the system dynamics are changing during operation. This is the case when the robot HyQ performs, for example, a walking task, its torque controlled legs need to support the full weight of the robot in stance phase and are only subjected to their own weight during flight phase while tracking a torque reference. Thus, the load conditions for a leg change quite heavily and rapidly, that is, the system dynamics change accordingly. Experiments on the real-time force control one-dimensional (FC1D) test set-up were carried out in order to assess the impact of such changes in load conditions.

Figure 1: Experimental results exemplifying the impact of changing system dynamics on the force tracking performance of a fixed gain torque controller.

Figure 1 shows the force tracking of a state-of-the-art feedback linearization controller for a sinusoidal force reference signal (black line). The blue line shows the force tracking for the controller designed for a system having load mass of 2.5 kg. The system dynamics are then altered by adding 20 kg of additional weight to the test set-up while keeping the controller gains the same. This added weight imitates the conditions of a leg in stance phase. The green line shows the force tracking of this fixed gain controller. Note that this experiment does not try to show perfect force tracking, it only exemplifies the impact of changing system dynamics. As can be seen, the force tracking performance using the same controller decreases when adding weight to the test set-up, that is, when the system dynamics change. In general, fixed gain controllers are not able to give consistent performance when the system dynamics change, thus a low-level controller is seeked for that adapts itself to the environment.


<latex> {\fontsize{13pt}\selectfont \textbf{Nonlinear Model of the Hydraulic System} </latex>

<latex> {\fontsize{10pt}\selectfont \textbf{Layout and Specification} </latex>

Figure 2: Free-body diagram of the combined system consisting of a hydraulic cylinder, valve, load cell, and load mass. All relevant dimensions and forces are drawn.

The hydraulic system consists of an asymmetric double acting cylinder with a valve which controls the flow of fluid between the two chambers, shown on the left side in figure 2. A piston inside the cylinder creates these two chambers. The piston moves due to the applied pressure difference across the two chambers. A single rod is rigidly attached at the right side of the piston, which can be used to connect a load. The pressure inside the two chambers is controlled by a valve. The valve consists of a spool which opens or closes the ports connecting the pressure source (or reservoir) and the two chambers. The load mass system, shown on the right in figure 2, consists of a mass which is guided along the direction of the cylinder stroke by axial bearings on a cylindrical shaft. These bearings introduce friction acting in opposite direction of motion. In addition, springs are considered which are placed between cart and end-stop on both sides. The springs and friction terms can be understood as modeling stiffness and damping of the environment the cylinder load mass system is operated in. The end of the cylinder rod is connected to the rod of the load mass and a load cell (force sensor) is mounted in between.

For modeling purposes, the combined system is cut in two parts in order to derive the equations of motion and to reveal the internal forces. Figure 2 shows the free-body diagram and all relevant dimensions and forces are drawn. It is assumed that only the load $m_l$ and the piston $m_p$ have mass, the rod and load cell connecting load to cylinder are considered to be an ideal connection, thus infinitely stiff and without mass. The friction is drawn as a force acting in opposite direction of motion, noted as $F_{pf}$ for the piston friction and $F_{Lf}$ for the load mass friction. The springs are attached to the load mass and environment, with $F_1$ and $F_2$ being the two spring forces and $L_{01}$, $L_{02}$ denoting their unstressed length, respectively. The load cell is assumed to be massless (and thus does not need a coordinate) and its resonance frequency is at around 12 kHz, which means that its relevant dynamics are at frequencies one decade higher than those of the dynamics of the cylinder load mass system. Therefore, the sensor dynamics can be neglected. The internal forces $F_{cp}$ and $F_{cL}$ appear due to cutting open the connecting rod just before and after the load cell. The hydraulic force acts on the piston and is positive in positive $x_p$ direction. The fluid flowing into chamber A is denoted by $q_a$ and is positive denoted by the arrow beneath, the flow out of chamber B is denoted by $q_b$ and positive when flowing out, denoted by the corresponding arrow beneath.


<latex> {\fontsize{10pt}\selectfont \textbf{Modeling the Load Cell} </latex>
The load cell is a force sensor which typically consists of a membrane perpendicular to the direction of the force. We neglect the dynamics of the load cell, as already mentioned above, and assume it to be massless and infinitely stiff. From the first assumption, it immediately follows from figure 2 that a simple force balance must hold: $F_{cp} = - F_{cL}$ The second assumption implies that we can measure the applied force exactly, thus we define the sensor-force as $F_s = - F_{cp}$ where a unit measurement gain is assumed. The load cell force measurement is then given by: \begin{equation*} \begin{split}

F_s & = F_h - d_p\cdot \dot{x}_p - m_p \cdot \ddot{x}_p \qquad \qquad \quad \text{(left side)} \qquad \text{(1)}\\ 
    & = (k_1 + k_2) \cdot y + d_l \cdot \dot{y} + m_l \cdot \ddot{y}   \qquad \text{(right side)}

\end{split} \label{eq:measurement_equation_load_cell} \end{equation*} As can be seen, the load cell measures not only the hydraulic force, but also the forces due to friction and inertia. This equation usually confuses people since one would expect only one equation. The fact that we chose to cut free the complete system made it necessary to define two system boundaries for the left system and for the right system shown in figure 2. Due to Newton equations (the momentum balance), the previous internal forces acting on the load cell are now external forces for these two systems and thus they appear in both equations. When connecting the two systems back together, these forces become internal forces again and disappear.


<latex> {\fontsize{10pt}\selectfont \textbf{Nonlinear Model} </latex>
We can write the equation of motion for the combined system, using the above equation for the load cell force measurement, as: \begin{equation*} (m_l+m_p)\cdot \ddot y + (d_l+d_p)\cdot \dot y +(k_1 + k_2)\cdot y = A_p \cdot (p_a - \alpha\cdot p_b) \qquad \text{(2)} \end{equation*}

In state-space notation the full nonlinear equation using a simplified valve spool model relating $x_v$ to $u_v$, can be written as follows: for $u_v > 0$ we have: \begin{equation*} \ddot{\vec{x}} = f^+_{u_v}(\vec x,u_v) \rightarrow \left( \begin{array}{l} \dot{x}_p
\ddot{x}_p
\dot{p}_a
\dot{p}_b
\end{array}\right) = \begin{bmatrix} \dot{x}_p
\frac{1}{M}\left( -B \dot{x}_p - C (x_p-\frac{L_c}{2})\right) + \frac{A_p}{M}(p_a - \alpha p_b)
\frac{\beta_e}{V_{pl}+x_p A_p} \left( K_v |u_v| \sqrt{p_s - p_a} - A_p \dot{x}_p \right)
\frac{\beta_e}{V_{pl}+(L_c-x_p)\alpha A_p} \left(- K_v |u_v| \sqrt{p_b - p_t} + \alpha A_p \dot{x}_p \right)
\end{bmatrix} \qquad\text{(3)} \end{equation*} and for $u_v < 0$: \begin{equation*} \ddot{\vec{x}} = f^-_{u_v}(\vec x,u_v) \rightarrow \left( \begin{array}{l} \dot{x}_p
\ddot{x}_p
\dot{p}_a
\dot{p}_b
\end{array}\right) = \begin{bmatrix} \dot{x}_p
\frac{1}{M}\left( -B \dot{x}_p - C (x_p-\frac{L_c}{2})\right) + \frac{A_p}{M}(p_a - \alpha p_b)
\frac{\beta_e}{V_{pl}+x_p A_p} \left(- K_v |u_v| \sqrt{p_a - p_t} -A_p \dot{x}_p\right)
\frac{\beta_e}{V_{pl}+(L_c-x_p)\alpha A_p} \left( K_v |u_v| \sqrt{p_s - p_b} + \alpha A_p \dot{x}_p\right)
\end{bmatrix} \qquad \text{(4)} \end{equation*}


<latex> {\fontsize{10pt}\selectfont \textbf{Linear Model using the Load Cell Force} </latex>
The nonlinear model derived above has one significant drawback, that is, the state vector is not fully measurable since we do not measure the pressure inside the cylinder chambers. However, it can be seen that what drives the piston is just the pressure difference $p_l = p_a - \alpha p_b$, called load pressure. This simplification allows us to reduce the order of the state space system. For the linearization we need the load pressure dynamics purely as a function of itself and possibly the other states, thus: \begin{equation*} \dot{p}_l = f(p_l, x_p, \dot{x}_p, u_v) \qquad \text{(5)} \end{equation*} where $f(\dots)$ is some function of the arguments. This relationship can be derived by assuming a steady-state pressure condition which has the property that the pressure dynamics are zero: $\dot{p}_a = 0 \qquad \dot{p}_b = 0$. The above nonlinear load pressure function (5) did reduce the number of states, however, the state vector is still not fully measurable, hence the load cell force measurement equation (1) is used to substitute the term $F_h = A_p \cdot p_l$ in the nonlinear equations (3), (4) of motion above. The load pressure dynamics is replaced by the load cell force dynamics, having a form like: $\dot{F}_s = f(x_p, \dot{x}_p, F_s, u_v)$.

The simplified system can now be written in state space form with the load cell force state: \begin{equation*} \tilde x = \begin{pmatrix} x_1
x_2
x_3 \end{pmatrix} = \left( \begin{array}{l} x_p \text{ = position of piston}
\dot{x}_p \text{ = velocity of piston}
F_s \text{ = load cell force}
\end{array}\right) \qquad \text{(6)} \end{equation*} The measurement vector is now just the same as the state vector since all states are measured: \begin{equation*} \vec y = \vec x \qquad \text{(7)} \end{equation*}


<latex> {\fontsize{13pt}\selectfont \textbf{Model Analysis} </latex>
This section analyses how the system behavior changes when the operating point or the values of the model parameters are varied. First, the influence of the operating point is analyzed since the linearized system is only valid around its operating point chosen for the linearization. The range of validity is determined by the nonlinearity of the underlying nonlinear system. If, for example, the nonlinear system behaves almost linearly, then the validity of the linearized system will span a large set of operating points. If, however, the nonlinear system behaves strongly nonlinear, then the validity of the linear system will be limited to a small range.

The difference in the “Degree of Nonlinearity” analysis and the “Parameter Sensitivity” analysis is that the dynamics of changing operating points are inherently included in the nonlinear system, whereas variations in the modeling parameters, such as mass and friction, affect both the nonlinear and the linear models.


<latex> {\fontsize{10pt}\selectfont \textbf{Degree of Nonlinearity} </latex>
The “Degree of Nonlinearity” of the nonlinear model (3), (4) is studied by linearizing it at different operating points. The nominal operating point is defined for a cylinder at rest and has a complexity of four dimensions because there are four variables defining the operating point. The influence of each variable is looked at first while the others remain fixed. It turns out that varying the operating point of the valve $u_{v\oslash}$ results in the most dramatic change. The individual influence of the other three operating points is smaller. Hence, figure 3 shows the changes of the load cell force transfer function for the nominal operating point $u_v = 0 \%$ and fully open valve $u_v = \pm 100 \%$.

Figure 3: Degree of Nonlinearity for different valve operating points Figure 4: Degree of Nonlinearity for varying all operating points

It can clearly be seen how the force $F_h = A_p \cdot p_l$ created by the load pressure dynamics (5) dominates the resonance peak of the hydraulic system. The response magnitude of the fully negative open valve (red) is less than that of the positive open valve (green) because the hydraulic cylinder is asymmetric, hence less force is created in negative direction. The equivalent valve position $u_v$ is a direct input of this load pressure equation amplified by the valve gain $K_v$, hence its strong influence. This behavior introduces some unwanted changes in the dynamics of the system. As one can imagine, when applying certain reference trajectories, the range of the valve inputs will span its full range. Hence, the system response is different at every instance. Figure (4) shows the extent the transfer functions change when letting the operating point vary through the complete state space. Shown are the responses of $2400$ different systems calculated by linearizing the nonlinear model around operating points varying between $10 \%$ and $ 190 \%$ of their nominal value. As can be seen, the fundamental characteristic of the transfer functions remains approximately the same; however, the resonance peak is damped more or less, depending on the operating point. Note that the whole range of transfer functions can be captured by the three (or even two) transfer functions shown in figure 3. One system for the “undamped” response and a second one for the “damped” response are essentially sufficient to describe the region the nonlinear system occupies.


<latex> {\fontsize{10pt}\selectfont \textbf{Parameter Sensitivity} </latex>
The dynamics of the hydraulic system depend to a large degree on the values of the mass, friction coefficient and spring stiffness. These three parameters are varied while the others are held at their nominal values, respectively. Figure 5 shows the effect on the force transfer function due to varying load mass $m_l$ within the set: $m_l \in \left[1 kg, 127 kg\right]$. The color changes from black to yellow with increasing mass. The region around the nominal system is drawn in bright red. As can be clearly seen, the changes in mass shift the location of the resonance peak and also increase the magnitude for increasing weight. Figure 6 shows the movement of the pole locations due to varying mass $m_l$ and friction coefficient $d_l$. The color changes from black to yellow with increasing friction coefficient and, additionally, the color changes from blue to light green for increasing mass. As can be clearly seen, the changes in friction coefficient effectively pull the poles closer to the origin, thus making them more robust. The changes in mass have a profound effect on the location of the poles, which basically cover the complete unit circle.

Figure 5: Parameter sensitivity of the load cell force transfer function due to varying load mass $m_l$ Figure 6: Parameter sensitivity - pole locus of the linear model while varying the mass $m_l$ and friction coefficient $d_l$ at the same time.

All in all we can summarize that the hydraulic system has a high degree of nonlinearity due to the valve and pressure dynamics creating the hydraulic force. Identifying the underlying system for input signals exciting these nonlinearities will pose a difficult task for any estimator. The force transfer function (and system) is quite sensitive to changes in both mass $m_l$ and friction coefficient $d_l$, hence completely diverse systems for different parameters may result. Therefore, an adaptive controller makes sense to cope with these severe changes in the system dynamics.


<latex> {\fontsize{13pt}\selectfont \textbf{Adaptive Control Framework} </latex>
There are many ways on how to design an adaptive control framework, we have chosen a method where the time-varying system is first (recursively) estimated and this improved system knowledge is then used to calculate new controller gains. One advantage of this method is, usually, that it is generalizable since there are no system or task specific assumptions needed. Its disadvantage is, however, that the system and controller gains need to be recalculated even when the same task is executed repetitively, unless some logic is incorporated. We have chosen this method since it is additionally rather simple and computationally inexpensive, which is important since the adaptive framework will be implemented on real-time hardware. Moreover, the chosen approach is also modular, meaning that different estimators and controllers can be used without disturbing the adaptive control framework. With this structure, controller requirements can be changed without changing the estimation algorithm at all, which is in general not possible when using learning algorithms since these are typically more integrated. Our approach is therefore more general and modular. Moreover, since there are no explicit model assumptions needed, our adaptive framework can be used for any robot, will it be electrically or hydraulically actuated. Different degrees of freedom are also possible. The same framework can, for example, be used for the legs of the robot HyQ as well as for its arms (currently under development).

Figure 7: Flow chart of the adaptive control framework

Figure 7 shows the flow chart of the chosen adaptive control framework. Inputs (e.g. measurements and reference signals) are fed to the controller which then acts on the system (robot). The system (robot) performs the desired actions. Some measurements are taken which the estimator uses to come up with the best estimate of the system (robot). This improved knowledge is then used by an update algorithm which calculates new controller gains. These gains are then fed into the controller and the adaption cycle starts again.


<latex> {\fontsize{10pt}\selectfont \textbf{Adaptive Control Framework - Controller} </latex>
Above a linear system model in terms of a fully measurable state vector was derived, thus enabling full state feedback control without the need for an observer (e.g. a Linear Quadratic Gaussian (LQG) controller). Therefore, the first and most obvious choice is to use a Linear Quadratic Regulator (LQR) not only taking advantage of the fully measurable state but also (and very important) providing a guaranteed (minimum) phase margin of $\pm 60^\circ$ for all controlled inputs of the system10). This guaranteed phase margin has the advantage that the controller is more robust against estimation errors of the system matrices. Additionally, because of full state feedback, the LQR controller has the velocity compensation concept 11) already “built-in” because the velocity of the load $\dot{x}_l$ is part of the state. There are only a few parameters that need to be tuned, namely the weighting matrices for the states $Q$ and inputs $R$ (sometimes the cross-weighting of states and inputs $N$ is also considered). Of course, the number of parameters depends on the size of the state vector. Usually, it is sufficient to limit the weighting matrices to belong to the class of diagonal matrices, therefore, greatly reducing the number of parameters. Once tuned, these parameters remain the same unaffected by system changes.


<latex> {\fontsize{10pt}\selectfont \textbf{Adaptive Control Framework - Estimator} </latex>
The estimation block (green) shown in figure 7 can consist of virtually any estimator as long as the inputs and outputs remain consistent with the framework. Again, due to the linear system model derived above, which suggests a linear relationship between unknowns and measurements, a very simple estimator, that is, a (linear) recursive least squares (RLS) estimator, was selected. This simple estimator was chosen due to several reasons. These are:

  • The unknown parameters, which are the elements of the system matrices, depend linearly on the measurements. Therefore, no additional model simplifications are needed to be able to write the system in terms of unknown parameters.
  • The estimator is able to estimate a discrete-time single-input and single-output (SISO) system as well as a multiple-input and multiple-output (MIMO) systems, hence the estimator is a rather general algorithm. The estimator can thus be used for any robot, will it be electric or hydraulically actuated, with any number of degrees of freedom.
  • There are no model assumptions necessary, fixing the measurement vector is sufficient. There is only one single parameter, that is, the forgetting factor $\lambda$.
  • The LQR controller requires a linear system, which the RLS estimator can provide directly.


<latex> {\fontsize{10pt}\selectfont \textbf{Adaptive Control Framework - Update Logic} </latex>
Figure 7 shows an additional block in red, which is the update logic responsible for calculating the new controller gains and, more importantly, deciding when to update the controller gains. As the time-varying system changes, the recursive estimator results in system descriptions mixing the response of the old system with the response of the actual system, thus resulting in unreliable system estimates. The idea of the update logic used in this thesis is to calculate and update the controller gains only when the estimated system is distinctively different enough from the current system the controller was calculated on. In essence, the controller is updated only when it is not able to deliver satisfactory performance and when the system estimate has converged to a new system description. The robustness capability of the controller is thus fully taken into account. The advantages of this method are that it minimizes the computational burden, considers the robustness of the controller, and is able to incorporate knowledge about the system and its estimator.


<latex> {\fontsize{13pt}\selectfont \textbf{Recursive System Identication Algorithm} </latex>
The basis for this identification idea is the discrete-time linear system description given by: \begin{equation*} \begin{split} x[k] &= \mathcal{A}[k-1] \cdot x[k-1] + \mathcal{B}[k-1] \cdot u[k-1]
y[k-1] &= \mathcal{C}[k-1] \cdot x[k-1] + \mathcal{D}[k-1] \cdot u[k-1] \end{split} \qquad \text{(8)} \end{equation*} The fundamental idea is to realize that we want to estimate the four transition matrices describing the linear system. It is therefore possible to rewrite the system description (8) as a linear equation in terms of the unknown parameters which are all the elements of the transition matrices. This idea has been mentioned in the past, for example, at the beginning of the paper 12) which discusses a subspace method for directly identifying linear models. However, we do not need to deploy subspace methods since we can measure the full state vector $\vec x$ along with output measurements $\vec y$.


<latex> {\fontsize{10pt}\selectfont \textbf{The Complete RLS Algorithm} </latex>
Reformulating the problem above into a linear equation relating the nth measurement to the unknown parameter vector $\Theta$ yields: $y[n] = H[n] \Theta + \omega[n]$ where $y[n]$ is the nth measurement, $H[n]$ is the regression matrix relating the measurement to the parameter and $\omega[n]$ is the measurement noise. The noise is assumed to be zero-mean white noise. The measurement $y[n]$ is assumed to be a vector. The parameter vector $\Theta$ is as long as the number of unknown elements. The solution $\Theta = (H^TW H)^{-1} H^T Wy$ is the “best” estimate of the unknown parameters using all past measurements up to time $n$, where $W$ is a weighting matrix, $y$ is a vector of all past measurements and $H$ is the full regression matrix connecting the unknown parameters to the measurement.

The recursive least squares estimation algorithm consists of the following equations: \begin{equation*} \boxed{ \begin{split} K(n) & = P(n-1) H^T[n] \cdot \Bigl[H[n]P(n-1)H^T[n] + \lambda\cdot I \Bigr]^{-1}
\Theta_n &= \Theta_{n-1} + K(n) \cdot \Bigl(y[n] - H[n] \cdot \Theta_{n-1}\Bigr)
P(n) & = \frac{P(n-1)}{\lambda}\cdot \biggl(I - H^T[n]\Bigl[H[n]P(n-1)H^T[n] + \lambda\cdot I \Bigr]^{-1}H[n]P(n-1) \biggr) \end{split}} \qquad \text{(9)} \end{equation*}

At each time step $[k]$ a latest estimate $\Theta_k$ of the state transition matrices (equation (8)) is obtained.


<latex> {\fontsize{13pt}\selectfont \textbf{Adaptive Control Synthesis} </latex>
The LQR controller is a linear state feedback controller whose gain $K$ is calculated using the solution of the discrete-time algebraic Riccati equation (DARE) for some system matrix and some weighting matrices. The discrete-time system is: \begin{equation*} x[n+1] = \mathcal{A}\cdot x[n] + \mathcal{B}\cdot u[n] \qquad \text{(10)} \end{equation*} where $x$ denotes the state, $u$ is the input and $n$ is the current discrete-time step. The two matrices $\mathcal{A}$ and $\mathcal{B}$ describe the linear system. The resulting linear state feedback controller is: \begin{equation*} u[n] = - \mathcal{K} \cdot x[n] \qquad \text{(11)} \end{equation*} where $\mathcal{K}$ is the LQR-gain matrix. The linear quadratic regulator (LQR) minimizes the cost function 13): \begin{equation*} J(u) = \sum_{n=0}^{\infty} x[n]^T\cdot Q \cdot x[n] + u[n]^T \cdot R \cdot u[n] + 2\cdot x[n]^T \cdot N \cdot u[n] \qquad \text{(12)} \end{equation*} where $Q$ is the weighting matrix for the states, $R$ is the weighting matrix for the inputs and $N$ is the weighting matrix for the cross-coupling of state and input. The finite-time solution to this optimization problem is the DARE equation 14): \begin{equation*} \mathcal{A}^T\cdot S \cdot \mathcal{A} - S - \left(\mathcal{A}^T \cdot S \cdot \mathcal{B} + N\right)\cdot \left( \mathcal{B}^T \cdot S \cdot \mathcal{B} + R \right)^{-1}\cdot \left( \mathcal{B}^T\cdot S \cdot \mathcal{A} + N^T\right) + Q = 0 \qquad \text{(13)} \end{equation*} where the Riccati matrix $S$ is its solution. The LQR-gain matrix is the minimizer of this equation and is calculated as: \begin{equation*} \mathcal{K} = \left(\mathcal{B}^T\cdot S \cdot \mathcal{B} + R \right) ^{-1} \left( \mathcal{B}^T \cdot S \right) \qquad \text{(14)} \end{equation*} The input $u[n]$ is the optimal control signal that regulates the state to zero while minimizing the cost function $J(u)$. We are, however, interested in tracking the reference, thus the input $x[n]$ of equation (11) is substituted by the tracking error, that is: \begin{equation*} u[n] = - \mathcal{K} \cdot x[n] = - \mathcal{K} \cdot \left( r[k]- y[k] \right) = - \mathcal{K} \cdot e[k] \qquad \text{(15)} \end{equation*} Hence, the tracking error is regulated to zero.


<latex> {\fontsize{13pt}\selectfont \textbf{Simulation Results of the Adaptive Control Framework} </latex>
Let us now simulate the full adaptive control framework as outlined in above. This simulation uses the RLS estimator and the LQR controller discussed above. The simulated hydraulic system uses the parameters identified for the real-time FC1D test set-up. The system parameters load mass $m_l$ and load friction coefficient $d_l$ are changed according to figure 7. The input signal to the controller is a force reference, which is a multisine with frequencies $f = [2,5,10] Hz$ and amplitude $160 N$.

Figure 7: Variation of the system parameters load mass $m_l$ and load friction coefficient $d_l$ for simulating the full adaptive control framework. Figure 8: Time series plot of the simulation of the full adaptive control framework without activated adaption.

The goal of this simulation is to show the impact of the adaption on the force tracking performance, hence two figures are shown. The first figure 8 shows the force tracking without activated adaption, that is, the initial controller gains remain constant during the simulation. As can be clearly seen, the tracking performance is disappointing. The closed-loop system even becomes unstable for high mass situations (second and fourth quarter). Only when the system is near the nominal system (first and third quarter) the controller was designed for, the response is fairly good. Hence the adaption is now activated, shown in figure 9, using the exact same simulation and settings.

Figure 9: Time series plot of the simulation of the full adaptive control framework with activated adaption.

It is immediately evident that the force tracking has improved significantly for high mass and/or high damping siuations as well as improved the force tracking of the stable set of parameters (3rd quarter). At the beginning of the first quarter of figure 9, the controller is not changed, thus the gains for a system with load mass $m_l = 0.5 kg$ are used. This results in a phase delay, as is clearly seen by the blue (reference signal $r(t)$) and green (measured force $y(t)$) force signals. At around $0.4 s$, the system is identified and the update logic allows the controller to update its gains. The system response immediately improves, although still being in the transient phase as the next system change to a load mass of $m_l = 50 kg$ occurs (second quarter). During the first $80 ms$, the gains are updated several times while still being in the transient phase. After this phase, the system is correctly identified and the proper controller gains are calculated. The force tracking is very good with minimal overshoot and no phase delay. During the third quarter, the system has again very low mass, but the transient phase is relatively short - the correct gains are found quickly.

All in all, we can summarize that the force tracking with activated adaption performs very well and shows promising results for implementing the proposed framework on the real-time hardware. The linear estimator does quite well (with the exception of the system with light mass) in identifying the system. The chosen multisine force reference signal apparently excites enough frequencies without exciting the nonlinearities of the system such that the estimator can identify all the relevant dynamics of the system. The multisine reference signal was specifically chosen to mimic a real-world reference signal for moving the legs of the robot HyQ.


<latex> {\fontsize{13pt}\selectfont \textbf{Estimator Experiments on the FC1D Test Set-Up} </latex>
An extensive amount of experiments on the real-time FC1D test set-up were carried out in order to assess the performance of the recursive linear estimator for various conditions: different input signal frequencies, different input signal amplitudes, and different types of input signals (e.g. chirp or sine signals). Figure 10 shows the load cell force transfer function of such an experiment. The (normalized) transfer functions are calculated (post-processed) from the state space matrices created using the estimated parameter vector $\Theta$ at each time step. The initial guess is drawn in black and the truth (calculated using non-causal estimation techniques) is drawn in blue. The colors of the estimates change from black to yellow for each time step, whereas the last estimate within the time window is drawn in green. The input signal is a chirp sine wave with frequencies ranging from $0 Hz - 30 Hz$, an amplitude of $ 20 \%$ of the nominal valve opening, and a duration of $8 s$. The forgetting factor is $\lambda = 0.9$.

Figure 10: Bode plot of transfer function estimates (normalized) for each time step using FC1D test set-up.

Several things are worth to point out:

  • The estimates quickly diverge from the initial estimate (bold black line) to intermediate estimates drawn in red. Within this first phase of the chirp signal, where the frequency content is still low, the system is not fully excited, hence the estimated transfer functions contain no resonance peak and are essentially straight lines.
  • As soon as the chirp signal excites the system enough; the resonance peak of the hydraulic system dynamics is identified by the estimator. The peak is gradually appearing within the estimates as they change color from red to yellow with increasing time.
  • Towards the end of the chirp signal, the system is fully excited and the estimator gives an almost exact estimate of the true system (blue line).
  • The true transfer function was calculated using similar chirp signals, but using non-causal and nonlinear estimation techniques provided by the system identification toolbox of MATLAB.

To summarize we can say that the linear estimator is able to identify the essential dynamics of the hydraulic system not only in simulation, but also on the real-time hardware.


<latex> {\fontsize{13pt}\selectfont \textbf{Controller Experiments on the FC1D Test Set-Up} </latex>
Figure 11 compares the force tracking capabilities of the LQR controller to those of the state-of-the-art feedback linearization (FL) controller. The FL controller was first implemented into the FC1D code and then tuned to give a satisfactory performance. The experiments were performed in the same fashion as those for the LQR controller.

When comparing the responses, shown in figure 11, it can be seen that the force tracking performance is almost identical, hence both controllers are able to give satisfactory performance to a well-known system remaining close to the operating point the controller was designed for. Note that this LQR controller does not use feedback linearization or velocity feedback compensation, but is still able to give good force tracking since it uses state feedback. The performance of the FL controller might be improved by more extensive tuning, especially regarding the small overshoot present for the reference signal shown at the bottom of figure 11.

Figure 11: Comparison of the force tracking capabilities of the FL controller versus the LQR controller. Figure 12: Force tracking performance of the fixed gain LQR controller for a $3.5 Hz$ sinusoidal reference.

The idea of the next test is to show the potential increase in force tracking performance that can be gained when using the right controller for the system. Also the robustness of the LQR controller is investigated. The LQR controller for the nominal system (load mass $m_l = 2.5 kg$) is used, but this time weight is added to the cart to alter the system dynamics. The test set-up is initialized with a nominal weight of $2.5 kg$, then the controller is selected and a reference signal is commanded. While the controller tracks the reference, weight is added to the cart in $5 kg$ increments and the force tracking is observed. The impact on control performance for a sinusoidal reference signal with frequency $3.5 Hz$ and amplitude $120 N$ is shown in figure 12.

When examining figure 12, it can be seen that the LQR controller (with fixed gains) is able to cope with some small amounts of added weight $\leq 10 kg$ without much decrease in tracking performance. However, when adding more weight, e.g. $20 kg$ or $9$ times more than the nominal weight, the controller is no longer able to track the reference - it even becomes unstable. A similar experiment using a LQR controller designed for a system with heavy weight $+22 kg$ was also carried out. Weight was removed while the controller was tracking the reference. However, problems with the filter resulted in unreliable measurements. Nonetheless, a similar trend was observed as noted for the experiments above.


<latex> {\fontsize{13pt}\selectfont \textbf{Summary} </latex>
First, the hydraulic system dynamics were studied and a nonlinear system was obtained, where the influence of the load cell sensor, that is, the force measurement device, was examined more closely. A full linear and two simplified linear models were derived and extensively studied. It was found that the simplified model based on the load cell force measurement accurately reproduces the force when compared to the nonlinear model, hence little is lost due to the simplifications. Therefore, this simplified model (given by the equations (5)-(6)) was used throughout this thesis; it has the additional advantage of relaying on a state vector which is fully measurable. Thus, full state feedback controllers are eligible. A “Degree of Nonlinearity” study for the nonlinear system as well as a parameter sensitivity study of the most important model parameters were carried out. It was found that the hydraulic system is heavily nonlinear due to the highly nonlinear pressure dynamics, as can be seen in figure 4. Hence, this nonlinear behavior of the system might pose difficulties for an estimator trying to give accurate estimates of the underlaying system.

Secondly, the adaptive control framework was outlined and detailed. The framework is based on the concept of first estimating the system and then using this improved knowledge to update the controller accordingly. Hence, it is modular; the choice of estimator and controller is virtually free. For the estimator, a very simple linear recursive least squares approach and a linear quadratic regulator (LQR) were chosen since the state vector is fully measurable and, more importantly, the LQR guarantees $60^\circ$ of phase margin, hence good robustness against estimation errors.

Simulation results assess the performance of both estimator and controller. It was shown that the estimator is able to identify system changes accurately and quickly for ideal15) signals, that is, signals with high frequency content and low amplitude. However, the performance deteriorates as soon as non-ideal16) signals are used, such as sinusoidal signals having low frequency content and/or high amplitude17). These non-ideal signals do not excite enough frequencies of the system and/or they excite the nonlinearities of the system, hence both cases pose a difficult task for an estimator.

The full adaptive control framework, where the estimator and controller work together, was simulated and it was shown (see figure 9) that the new adaptive controller is able to cope with abrupt and large system changes that can occur when the robot HyQ performs, for example, a walking trot.

The framework was implemented in C++ on a real-time FC1D test set-up in order to perform experiments. Experiments were performed to asses the performance of both the estimator and controller on the real-time hardware. It was found (see figure 10) that the chosen estimator is able, for some ideal signals, to correctly identify (in real-time) the system dynamics. The performance of the controller was extensively verified and the controller performed at least as well as the state-of-the-art feedback linearization controller (with velocity compensation) currently used on HyQ. The potential increase in tracking performance that can be gained when using the right controller for the system was also shown. Preliminary experiments for the full adaptive control framework was also done, though it was found that the computational demand of the implementation was too high in order to let both estimator and controller (with activated adaption of the gains) be run simultaneously.


<latex> {\fontsize{13pt}\selectfont \textbf{Future Work} </latex>
The most important next step is to show the performance of the full adaptive control framework using the FC1D test set-up. Unfortunately, the new FC1D set-up, whose design was part of the thesis, needs to be brought to fully operating condition first. Successful experiments proofing the framework's capabilities then might lead to its implementation on a leg test set-up (HyL) and ultimately to its implementation on the full HyQ robot. The ultimate goal is to sustainably improve the versatility and capability of the robot HyQ.

Further experiments assessing the estimation performance may be needed, especially with regard to non-ideal signals. Other estimation algorithms might be worth considering, such as nonlinear estimators.

One advantage of the proposed framework is that it is virtually model-free, hence, one should be able to use the exact same code on a different robot without redesign. An electronically actuated robot could, for example, be used to show the framework's versatility since only the weighting matrices and specifications of the measurement and input signals need to be newly defined.

Sven Hubacher 2014/04/25 15:03

1)
Thiago Boaventura, Claudio Semini, Jonas Buchli, Marco Frigerio, Michele Focchi, and Darwin G. Caldwell. Dynamic torque control of a hydraulic quadruped robot. In Robotics and Automation (ICRA), 2012 IEEE International Conference on, pages 1889-1894, 2012.
2)
Claudio Semini. HyQ - Design and Development of a Hydraulically Actuated Quadruped Robot. Ph.d. dissertation, Istituto Italiano di Tecnologia (IIT) and University of Genoa, Italy, April 2010.
3)
Claudio Semini, Nikos G. Tsagarakis, Emanuele Guglielmino, Michele Focchi, Ferdinando Cannella, and Darwin G. Caldwell. “Design of HyQ – a hydraulically and electrically actuated quadruped robot”. In Proceedings of the Institution of Mechanical Engineers, Part I: Journal of Systems and Control Engineering, volume 225, pages 831–849, 2011.
4)
Victor Barasuol, Jonas Buchli, Claudio Semini, Marco Frigerio, Edson de Pieri, and Darwin G. Caldwell. “A reactive controller framework for quadrupedal locomotion on challenging terrain”. In Robotics and Automation (ICRA), 2013 IEEE International Conference on, pages 2554–2561, May 2013.
5)
Michele Focchi, Victor Barasuol, Ioannis Havoutis, Jonas Buchli, Claudio Semini, and Darwin G. Caldwell. Local Reex Generation for Obstacle Negotiation in Quadrupedal Locomotion. In Int. Conf. on Climbing and Walking Robots (CLAWAR), 2013.
6)
Stéphane Bazeille, Victor Barasuol, Michele Focchi, Ioannis Havoutis, Marco Frigerio, Jonas Buchli, Darwin G. Caldwell, and Claudio Semini. Quadruped robot trotting over irregular terrain assisted by stereo-vision. In Intelligent Service Robotics, volume 7, pages 67-77. Springer Berlin Heidelberg, 2014.
7)
Michele Focchi. Strategies To Improve the Impedance Control Performance of a Quadruped Robot. Ph.d. dissertation, Istituto Italiano di Tecnologia (IIT) and University of Genoa, Italy, April 2013.
8)
Thiago Boaventura. Hydraulic Compliance Control of the Quadruped Robot HyQ. Ph.d. dissertation, Istituto Italiano di Tecnologia (IIT) and University of Genoa, Italy, March 2013.
9)
Actually, it can never be fulfilled. However, an engineer's interpretation of the word perfect is anticipated.
10)
Sigurd Skogestad and Ian Postlethwaite. Multivariable Feedback Control: Analysis and Design, volume 2. Wiley New York, 2007.
11)
Thiago Boaventura, Michele Focchi, Marco Frigerio, Jonas Buchli, Claudio Semini, Gustavo A. Medrano-Cerda, and Darwin G. Caldwell. On the role of load motion compensation in high-performance force control. In Intelligent Robots and Systems (IROS), 2012 IEEE/RSJ International Conference on, pages 4066-4071, 2012.
12)
Lennart Ljung and Tomas McKelvey. A Least Squares Interpretation of Sub-Space Methods for System Identication. In Decision and Control, 1996., Proceedings of the 35th IEEE Conference on, volume 1, pages 335-342, December 1996.
13)
Brian D.O. Anderson and John B. Moore. Linear optimal control. Prentice-Hall Englewood Clis, NJ, 1971.
14)
Dimitri P. Bertsekas. Dynamic programming and optimal control, volume 1. Athena Scientic Belmont, MA, 1995.
15)
The term “ideal signals” classifies signals having high frequency content and low amplitude. Hence, exciting the system well, but not its nonlinearities.
16)
These are signals having low frequency content and high amplitude. Hence, not exciting the system sufficiently, but its nonlinearities.
17)
The qualitative meaning of amplitude is anticipated here since it does not matter if high amplitude signals are directly fed to the valve input or first as a force reference to the controller, because both cases excite the nonlinearities of the system.
adrl/education/completed_projects/sven2013f.txt · Last modified: 2014/05/21 06:48 (external edit)