digital-brain/content/phdthesis/li01_simul_fault_vibrat_isolat_point.md

20 KiB

+++ title = "Simultaneous, fault-tolerant vibration isolation and pointing control of flexure jointed hexapods" author = ["Dehaeze Thomas"] draft = false ref_author = "Li, X." ref_year = 2001 +++

Tags
[Stewart Platforms]({{< relref "stewart_platforms.md" >}}), [Vibration Isolation]({{< relref "vibration_isolation.md" >}}), [Cubic Architecture]({{< relref "cubic_architecture.md" >}}), [Flexible Joints]({{< relref "flexible_joints.md" >}}), [Multivariable Control]({{< relref "multivariable_control.md" >}})
Reference
(Li 2001)
Author(s)
Li, X.
Year
2001

Introduction

Flexure Jointed Hexapods

A general flexible jointed hexapod is shown in Figure 1.

{{< figure src="/ox-hugo/li01_flexure_hexapod_model.png" caption="<span class="figure-number">Figure 1: A flexure jointed hexapod. {P} is a cartesian coordinate frame located at, and rigidly attached to the payload's center of mass. {B} is the frame attached to the base, and {U} is a universal inertial frame of reference" >}}

Flexure jointed hexapods have been developed to meet two needs illustrated in Figure 2.

{{< figure src="/ox-hugo/li01_quet_dirty_box.png" caption="<span class="figure-number">Figure 2: (left) Vibration machinery must be isolated from a precision bus. (right) A precision paylaod must be manipulated in the presence of base vibrations and/or exogenous forces." >}}

Since only small movements are considered in flexure jointed hexapod, the Jacobian matrix, which relates changes in the Cartesian pose to changes in the strut lengths, can be considered constant. Thus a static kinematic decoupling algorithm can be implemented for both vibration isolation and pointed controls on flexible jointed hexapods.

On the other hand, the flexures add some complexity to the hexapod dynamics. Although the flexure joints do eliminate friction and backlash, they add spring dynamics and severely limit the workspace. Moreover, base and/or payload vibrations become significant contributors to the motion.

The University of Wyoming hexapods (example in Figure 3) are:

  • Cubic (mutually orthogonal)
  • Flexure Jointed

{{< figure src="/ox-hugo/li01_stewart_platform.png" caption="<span class="figure-number">Figure 3: Flexure jointed Stewart platform used for analysis and control" >}}

The objectives of the hexapods are:

  • Precise pointing in two axes (sub micro-radians)
  • simultaneously, providing both passive and active vibration isolation in six axes

Jacobian matrix, Dynamic model, and decoupling algorithms

Jacobian Matrix

The Jacobian matrix \(J\) relates changes in the cartesian pose \(\mathcal{X}\) to changes in the strut lengths \(l\):

\begin{equation} \delta l = J \delta \mathcal{X} \end{equation}

where \(\mathcal{X}\) is a 6x1 vector of payload plate translations and rotations

\begin{equation} \mathcal{X} = \begin{bmatrix} p_x & p_y & p_z & \theta_x & \theta_y & \theta_z \end{bmatrix} \end{equation}

\(J\) is given by:

\begin{equation} J = \begin{bmatrix} {}^B\hat{u}_1^T & [({}^B_PR^P p_1) \times {}^B\hat{u}_1]^T \\ \vdots & \vdots \\ {}^B\hat{u}_6^T & [({}^B_PR^P p_6) \times {}^B\hat{u}_6]^T \end{bmatrix} \end{equation}

where (see Figure 1) \(p_i\) denotes the payload attachment point of strut \(i\), the prescripts denote the frame of reference, and \(\hat{u}_i\) denotes a unit vector along strut \(i\). To make the dynamic model as simple as possible, the origin of {P} is located at the payload's center of mass. Thus all \({}^Pp_i\) are found with respect to the center of mass.

Dynamic model of flexure jointed hexapods

The dynamics of a flexure jointed hexapod can be written in joint space:

\begin{equation} \label{eq:hexapod_eq_motion} \begin{split} & \left( J^{-T} \cdot {}^B_PR \cdot {}^PM_x \cdot {}^B_PR^T \cdot J^{-1} + M_s \right) \ddot{l} + B \dot{l} + K (l - l_r) = \\ &\quad f_m - \left( M_s + J^{-T} \cdot {}^B_PR \cdot {}^PM_x \cdot {}^U_PR^T \cdot J_c \cdot J_b^{-1} \right) \ddot{q}_u + J^{-T} \cdot {}^U_BR^T(\mathcal{F}_e + \mathcal{G} + \mathcal{C}) \end{split} \end{equation}

where:

  • \({}^PM_x\) is the 6x6 mass/inertia matrix of the payload, found with respect to the payload frame {P}, whose origin is at the hexapod payload's center of mass
  • \({}^U_BR\) is the 6x6 rotation matrix from the base frame {B} to the inertial frame of reference {U} (it consists of two identical 3x3 rotation matrices forming a block diagonal 6x6 matrix). Similarly, \({}^B_PR\) is the rotation matrix from the payload frame to the base frame, and \({}^U_PR = {}^U_BR {}^B_PR\)
  • \(J\) is the 6x6 Jacobian matrix relating payload cartesian movements to strut length changes
  • \(M_s\) is a diagonal 6x6 matrix containing the moving mass of each strut
  • \(l\) is the 6x1 vector of strut lengths
  • \(B\) and \(K\) are 6x6 diagonal matrices containing the damping and stiffness, respectively, of each strut
  • \(l_r\) is the constant vector of relaxed strut lengths
  • \(f_m\) is the vector of strut motor force
  • \(J_c\) and \(J_b\) are 6x6 Jacobian matrices capturing base motion
  • \(\ddot{q}_u\) is a 6x1 vector of base acceleration along each strut
  • \(\mathcal{F}_r\) is a vector of payload exogenous generalized forces
  • \(\mathcal{C}\) is a vector containing all the Coriolis and centripetal terms
  • \(\mathcal{G}\) is a vector containing all gravity terms

Decoupling

Two decoupling algorithms are proposed by combining static input-output transformations with hexapod geometric design.

Define a new input and a new output:

\begin{equation} u_1 = J^T f_m, \quad y = J^{-1} (l - l_r) \end{equation}

Equation eq:hexapod_eq_motion can be rewritten as:

\begin{equation} \label{eq:hexapod_eq_motion_decoup_1} \begin{split} & \left( {}^B_PR \cdot {}^PM_x \cdot {}^B_PR^T + J^T \cdot M_s \cdot J \right) \cdot \ddot{y} + J^T \cdot B J \dot{y} + J^T \cdot K \cdot J y = \\ &\quad u_1 - \left( J^T \cdot M_s + {}^B_PR \cdot {}^PM_x \cdot {}^U_PR^T \cdot J_c \cdot J_b^{-1} \right) \ddot{q}_u + {}^U_BR^T\mathcal{F}_e \end{split} \end{equation}

If the hexapod is designed such that the payload mass/inertia matrix written in the base frame (\(^BM_x = {}^B_PR \cdot {}^PM_x \cdot {}^B_PR_T\)) and \(J^T J\) are diagonal, the dynamics from \(u_1\) to \(y\) are decoupled (Figure 4).

{{< figure src="/ox-hugo/li01_decoupling_conf.png" caption="<span class="figure-number">Figure 4: Decoupling the dynamics of the Stewart Platform using the Jacobians" >}}

Alternatively, a new set of inputs and outputs can be defined:

\begin{equation} u_2 = J^{-1} f_m, \quad y = J^{-1} (l - l_r) \end{equation}

And another decoupled plant is found (Figure 5):

\begin{equation} \label{eq:hexapod_eq_motion_decoup_2} \begin{split} & \left( J^{-1} \cdot J^{-T} \cdot {}^BM_x + M_s \right) \cdot \ddot{y} + B \dot{y} + K y = \\ &\quad u_2 - J^{-1} \cdot J^{-T} \left( J^T \cdot M_s + {}^B_PR \cdot {}^PM_x \cdot {}^U_PR^T \cdot J_c \cdot J_b^{-1} \right) \ddot{q}_u + {}^U_BR^T\mathcal{F}_e \end{split} \end{equation}

{{< figure src="/ox-hugo/li01_decoupling_conf_bis.png" caption="<span class="figure-number">Figure 5: Decoupling the dynamics of the Stewart Platform using the Jacobians" >}}

These decoupling algorithms have two constraints:

  1. the payload mass/inertia matrix must be diagonal (the CoM is coincident with the origin of frame \(\{P\}\))
  2. the geometry of the hexapod and the attachment of the payload to the hexapod must be carefully chosen

For instance, if the hexapod has a mutually orthogonal geometry (cubic configuration), the payload's center of mass must coincide with the center of the cube formed by the orthogonal struts.

Simultaneous Vibration Isolation and Pointing Control

Many applications require simultaneous vibration isolation and precision pointing.

The basic idea to achieve such objective is to use:

  • acceleration feedback to provide high-frequency vibration isolation
  • cartesian pointing feedback to provide low-frequency pointing

The compensation is divided in frequency because:

  • pointing sensors often have low bandwidth
  • acceleration sensors often have a poor low frequency response

The control bandwidth is divided as follows:

  • low-frequency disturbances are attenuated and tracking is accomplished by feedback from low bandwidth pointing sensors
  • mid-frequency disturbances are attenuated by feedback from band-pass sensors like accelerometer or load cells
  • high-frequency disturbances are attenuated by passive isolation techniques

Vibration Isolation

The system is decoupled into six independent SISO subsystems using the architecture shown in Figure 6.

{{< figure src="/ox-hugo/li01_vibration_isolation_control.png" caption="<span class="figure-number">Figure 6: Vibration isolation control strategy" >}}

One of the subsystem plant transfer function is shown in Figure 6

{{< figure src="/ox-hugo/li01_vibration_control_plant.png" caption="<span class="figure-number">Figure 7: Plant transfer function of one of the SISO subsystem for Vibration Control" >}}

Each compensator is designed using simple loop-shaping techniques. A typical compensator consists of the following elements:

  • first order lag-lead filter to provide adequate phase margin a the low frequency crossover
  • a second order lag-lead filter to increase the gain between crossovers and provide adequate phase margin at the high frequency crossover
  • a second order notch filter to cancel the mode at 150Hz
  • a second order low pass filter to provide steep roll-off and gain stabilize the plant at high frequency
  • a first order high pass filter to eliminate DC signals

The unity control bandwidth of the isolation loop is designed to be from 5Hz to 50Hz, so the vibration isolation loop works as a band-pass filter.

Despite a reasonably good match between the modeled and the measured transfer functions, the model based decoupling algorithm does not produce the expected decoupling. Only about 20 dB separation is achieve between the diagonal and off-diagonal responses.

Severe phase delay exists in the actual transfer function. This is due to the limited sample frequency and sensor bandwidth limitation.

The zero at around 130Hz is non-minimum phase which limits the control bandwidth. The reason is not explained.

Pointing Control Techniques

A block diagram of the pointing control system is shown in Figure 8.

{{< figure src="/ox-hugo/li01_pointing_control.png" caption="<span class="figure-number">Figure 8: Figure caption" >}}

The plant is decoupled into two independent SISO subsystems. The decoupling matrix consists of the columns of \(J\) corresponding to the pointing DoFs.

Figure 9 shows the measured transfer function of the \(\theta_x\) axis.

{{< figure src="/ox-hugo/li01_transfer_function_angle.png" caption="<span class="figure-number">Figure 9: Experimentally measured plant transfer function of \(\theta_x/\theta_{x_d}\)" >}}

A typical compensator consists of the following elements:

  • a first order low pass filter to increase the low frequency loop gain and provide a slope of -20dB/decade for the magnitude curve at the crossover
  • two complex zeros with high \(Q\) to provide adequate phase margin at the crossover
  • a pole after the zeros to decrease the excess gain caused by these zeros
  • a second order notch filter to cancel the mode at 150Hz
  • a second order low pass filter to provide steep roll off and gain stabilize the plant at high frequency

The unity control bandwidth of the pointing loop is designed to be from 0Hz to 20Hz.

A feedforward control is added as shown in Figure 10. \(C_f\) is the feedforward compensator which is a 2x2 diagonal matrix. Ideally, the feedforward compensator is an invert of the plant dynamics.

{{< figure src="/ox-hugo/li01_feedforward_control.png" caption="<span class="figure-number">Figure 10: Feedforward control" >}}

Simultaneous Control

The simultaneous vibration isolation and pointing control is approached in two ways:

  1. Closing the vibration isolation loop first: Design and implement the vibration isolation control first, identify the pointing plant when the isolation loops are closed, then implement the pointing compensators.
  2. Closing the pointing loop first: Reverse order.

Figure 11 shows a parallel control structure where \(G_1(s)\) is the dynamics from input force to output strut length.

{{< figure src="/ox-hugo/li01_parallel_control.png" caption="<span class="figure-number">Figure 11: A parallel scheme" >}}

The transfer function matrix for the pointing loop after the vibration isolation is closed is still decoupled. The same happens when closing the pointing loop first and looking at the transfer function matrix of the vibration isolation.

However, the interaction between loops may affect the transfer functions of the first closed loop, and thus affect its relative stability.

The dynamic interaction effect:

  • Only happens in the unity bandwidth of the loop transmission of the first closed loop.
  • Affect the closed loop transmission of the loop first closed (see Figures 12 and 13)

As shown in Figure 12, the peak resonance of the pointing loop increase after the isolation loop is closed. The resonances happen at both crossovers of the isolation loop (15Hz and 50Hz) and they may show of loss of robustness.

{{< figure src="/ox-hugo/li01_closed_loop_pointing.png" caption="<span class="figure-number">Figure 12: Closed-loop transfer functions \(\theta_y/\theta_{y_d}\) of the pointing loop before and after the vibration isolation loop is closed" >}}

The same happens when first closing the vibration isolation loop and after the pointing loop (Figure 13). The first peak resonance of the vibration isolation loop at 15Hz is increased when closing the pointing loop.

{{< figure src="/ox-hugo/li01_closed_loop_vibration.png" caption="<span class="figure-number">Figure 13: Closed-loop transfer functions of the vibration isolation loop before and after the pointing control loop is closed" >}}

From the analysis above, it is hard to say which loop has more significant affect on the other loop, but the isolation loop adds a second resonance peak at its high frequency crossover in the pointing closed loop transfer function, which may cause instability. Thus, it is recommended to design and implement the isolation control system first, and then identify the pointing plant with the isolation loop closed.

Experimental results

Two hexapods are stacked (Figure 14):

  • the bottom hexapod is used to generate disturbances matching candidate applications
  • the top hexapod provide simultaneous vibration isolation and pointing control

{{< figure src="/ox-hugo/li01_test_bench.png" caption="<span class="figure-number">Figure 14: Stacked Hexapods" >}}

First, the vibration isolation and pointing controls were implemented separately. Using the vibration isolation control alone, no attenuation is achieved below 1Hz as shown in figure 15.

{{< figure src="/ox-hugo/li01_vibration_isolation_control_results.png" caption="<span class="figure-number">Figure 15: Vibration isolation control: open-loop (solid) vs. closed-loop (dashed)" >}}

The simultaneous control is of dual use:

  • it provide simultaneous pointing and isolation control
  • it can also be used to expand the bandwidth of the isolation control to low frequencies because the pointing loops suppress pointing errors due to both base vibrations and tracking

The results of simultaneous control is shown in Figure 16 where the bandwidth of the isolation control is expanded to very low frequency.

{{< figure src="/ox-hugo/li01_simultaneous_control_results.png" caption="<span class="figure-number">Figure 16: Simultaneous control: open-loop (solid) vs. closed-loop (dashed)" >}}

Summary and Conclusion

A parallel control scheme is proposed in this chapters. This scheme is suitable for simultaneous vibration isolation and pointing control. Part of this scheme involves closing one loop first, then re-identifying and designing the new control before closed the other loop.

An investigation into the interaction between loops shows that the order of closing loops is not important. However, only two channels need to be re-designed or adjusted for the pointing loop if the isolation loop is closed first. Experiments show that this scheme takes advantage of the bandwidths of both pointing and vibration sensors, and provides vibration isolation and pointing controls over a broad band.

Future research areas

Proposed future research areas include:

  • Include base dynamics in the control: The base dynamics is here neglected since the movements of the base are very small. The base dynamics could be measured by mounting accelerometers at the bottom of each strut or by using force sensors. It then could be included in the feedforward path.
  • Robust control and MIMO design
  • New decoupling method: The proposed decoupling algorithm do not produce the expected decoupling, despite a reasonably good match between the modeled and the measured transfer functions. Incomplete decoupling increases the difficulty in designing the controller. New decoupling methods are needed. These methods must be static in order to be implemented practically on precision hexapods
  • Identification: Many advanced control methods require a more accurate model or identified plant. A closed-loop identification method is propose to solve some problems with the current identification methods used.
  • Other possible sensors: Many sensors can be used to expand the utility of the Stewart platform:
    • 3-axis load cells to investigate the Coriolis and centripetal terms and new decoupling methods
    • LVDT to provide differential position of the hexapod payload with respect to the base
    • Geophones to provide payload and base velocity information

Bibliography

Li, Xiaochun. 2001. “Simultaneous, Fault-Tolerant Vibration Isolation and Pointing Control of Flexure Jointed Hexapods.” University of Wyoming.