DOI QR코드

DOI QR Code

Single-axis Hardware in the Loop Experiment Verification of ADCS for Low Earth Orbit Cube-Satellite

  • Choi, Minkyu (Mechanical and Aerospace Engineering and the Institute of Advanced Aerospace Technology, Seoul National University) ;
  • Jang, Jooyoung (Mechanical and Aerospace Engineering and the Institute of Advanced Aerospace Technology, Seoul National University) ;
  • Yu, Sunkyoung (Mechanical and Aerospace Engineering and the Institute of Advanced Aerospace Technology, Seoul National University) ;
  • Kim, O-Jong (Mechanical and Aerospace Engineering and the Institute of Advanced Aerospace Technology, Seoul National University) ;
  • Shim, Hanjoon (Mechanical and Aerospace Engineering and the Institute of Advanced Aerospace Technology, Seoul National University) ;
  • Kee, Changdon (Mechanical and Aerospace Engineering and the Institute of Advanced Aerospace Technology, Seoul National University)
  • Received : 2017.07.21
  • Accepted : 2017.08.18
  • Published : 2017.12.15

Abstract

A 2U cube satellite called SNUGLITE has been developed by GNSS Research Laboratory in Seoul National University. Its main mission is to perform actual operation by mounting dual-frequency global positioning system (GPS) receivers. Its scientific mission aims to observe space environments and collect data. It is essential for a cube satellite to control an Earth-oriented attitude for reliable and successful data transmission and reception. To this end, an attitude estimation and control algorithm, Attitude Determination and Control System (ADCS), has been implemented in the on-board computer (OBC) processor in real time. In this paper, the Extended Kalman Filter (EKF) was employed as the attitude estimation algorithm. For the attitude control technique, the Linear Quadratic Gaussian (LQG) was utilized. The algorithm was verified through the processor in the loop simulation (PILS) procedure. To validate the ADCS algorithm in the ground, the experimental verification via a single axis Hardware-in-the-loop simulation (HILS) was used due to the simplicity and cost effectiveness, rather than using the 3-axis HILS verification (Schwartz et al. 2003) with complex air-bearing mechanism design and high cost.

Keywords

1. INTRODUCTION

A payload in a cube satellite is generally dependent on the mission purpose. Seoul National University GNSS Laboratory satellITE (SNUGLITE) has the following payloads: dual-frequency(L1/L2) GPS receivers, boom structure and fine magnetometer to observe the Earth magnetic field (Kim et al. 2016). As reference sensors for the Attitude Determination and Control System (ADCS), sun sensors and magnetometer are used, while as a rate sensor, gyroscopes are mainly used (Ni & Zhang 2011). Coarse sun sensors have accuracy within 5–10° in general, whereas expensive fine sun sensors have a better accuracy within 0.01°. SNUGLITE uses an inexpensive photodiode-type coarse sun sensor as a sensor for attitude determination sensor, and also employs three-axis magnetometer and three-axis gyroscope for attitude determination sensor (Jang et al. 2016).

Estimation algorithms using attitude determination sensors can be typically divided into statistical estimation methods using quaternion such as QUEST (Ran et al. 2014), REQUEST, extended Kalman filter (EKF), and deterministic estimation methods including TRIAD algorithm. The TRIAD algorithm is used as the estimation algorithm during the initial stage, and then EKF is used to estimate the attitude of satellite. For the reference coordinate, a magnetic field model of the International Geomagnetic Reference Field (IGRF)-12 provided by the International Association of Geomagnetism and Aeronomy (IAGA), and DE405 solar model in the NASA Jet Propulsion Laboratory (JPL) were used.

In addition, a magnetorquer using magnet moment and reaction wheel or control moment gyro (CMG) are used as an actuator for control. Since the reaction wheel or CMG employs a motor, they consume more power than the magnetorquer. Furthermore, since an additional actuator is needed for moment dumping, three-axis magnetorquer was used in this study due to the low consumption, lightweight, and good control reliability. For the control algorithm, the Linear Quadratic Gaussian (LQG) was used to generate a control gain in real time.

To develop a cube satellite, generally, the following steps are needed: first, an algorithm is designed through Software in the Loop Simulation (SILS) that verifies the algorithm in terms of software simulation. Next, the algorithm is implemented directly in the processor on-board computer (OBC) to verify the ADCS algorithm of the actual flight model (FM) through the Processor in the Loop Simulation (PILS) in real time. Finally, the ADCS algorithm is experimentally verified by simulating the space environment to validate the attitude estimation and control performance as well as the algorithm through the Hardware in the Loop Simulation (HILS). In the HILS verification, attitude estimation and control performance are verified through experimental procedure using air-bearing-based HILS simulator that is mechanically complex and has high design cost for three-axis attitude determination and control (Schwartz et al. 2003). Through this process, the ADCS algorithm in the cube satellite is finally designed and verified.

In this paper, PILS that is implemented in actual OBC is discussed; and lower cost and more practical single-axis HIL experimental verification, in contrast with the HILS verification process using air-bearing, was presented (Ure et al. 2011). In particular, actual payload sensors should be used. Thus, a study on the sensors error modeling and compensation is also conducted.

2. ADCS ALGORITHM

2.1 Coordinate Frames

In this study, a number of coordinate systems are used. The Earth-centered inertial (ECI) coordinate system is a coordinate system that represents a position of one point in the space based on the origin in the center coordinate system of the Earth mass. In the ECI coordinate system, the Earth's equatorial plane is set to X and Y axes. The X-axis refers to the Vernal equinox; the Z-axis a vertical line in the North Pole direction in the XY plane; and the Y-axis an axis that is perpendicular to the X and Y axes. Next, the Earth-centered Earth Fixed (ECEF) coordinate system is used, in which the X-axis of the ECI frame is fixed in the Greenwich meridian direction and thereby is rotated around the Earth's rotation axis. This can be seen in Fig. 1, in which the Z-axis is defined as the Earth's center direction from the mass center of the satellite, and the Y-axis is defined as an outer product between Z-axis and velocity direction of the satellite. The X-axis refers to an outer product between the Y and X axes. In addition, the body frame that represents an attitude of the satellite is defined by the Euler angle as shown in Fig. 2. As described in the Introduction, the solar position model (JPL DE405) calculates a solar position through the ECI coordinate, and the Earth's magnetic field model (IGRF-12) is a model for the Earth's magnetic field. Thus, the ECEF coordinate system belongs to this (Kim 2015).

f1.jpg 이미지
Fig. 1. ECI, ECEF, local, body frame in space.

f2.jpg 이미지
Fig. 2. Difference between flight model (FM) and engineering model (EM) of ADCS.

2.2 Attitude Determination Based on EKF

For the EKF to estimate the attitude state of the cube satellite, a linear Kalman filter, which linearized a non-linear system at the nominal point, was used (Jang 2016). Eq. (1) expresses the attitude information of the satellite. \(\hat{\mathbf{x}}(t)\) refers to quaternions, \(\hat{\mathbf{\omega}}(t)\) an angular rate, and \(\hat{\mathbf{b}}(t)\) a gyro bias. The superscript of each variable expresses an estimate.

\(\hat{\mathbf{x}}(t)=\left[\begin{matrix}\hat{\mathbf{q}}(t)\\\hat{\mathbf{\omega}}(t)\\\hat{\mathbf{b}}(t)\\\end{matrix}\right]_{10\times1},\begin{matrix}\mathrm{\ \ \ \ \ \ \ \ }\hat{\mathbf{q}}=\left[\begin{matrix}q_0&q_1&q_2&q_3\\\end{matrix}\right]^T\\\mathrm{\ \ \ }\hat{\mathbf{\omega}}=\left[\begin{matrix}\omega_1&\omega_2&\omega_3\\\end{matrix}\right]^T\\\hat{\mathbf{b}}=\left[\begin{matrix}b_1&b_2&b_3\\\end{matrix}\right]^T\\\end{matrix}\)                                                                                            (1)

The kinematics equation of quaternion can be notated as it is divided into quaternion \(\hat{\mathbf{q}}(t)\) and angular velocity \(\hat{\mathbf{\omega}}(t)\) as presented in Eq. (2).

\(\dot{\hat{\mathbf{q}}}(t)=\frac{1}{2}\mathbf{\Omega}(\hat{\mathbf{\omega}}(t))\hat{\mathbf{q}}(t)=\frac{1}{2}\mathbf{\Xi}(\hat{\mathbf{q}}(t))\hat{\mathbf{\omega}}(t)\)                                                                                                   (2)

\(\mathbf{\Omega}(\mathbf{\omega})=\left[\begin{matrix}0&-\omega_1&-\omega_2&-\omega_3\\\omega_1&0&\omega_3&-\omega_2\\\omega_2&-\omega_3&0&\omega_1\\\omega_3&\omega_2&-\omega_1&0\\\end{matrix}\right]_{4\times4}\mathbf{\Xi}\left(\mathbf{q}\right)=\left[\begin{matrix}-q_1&-q_2&-q_3\\q_0&-q_3&q_2\\q_3&q_0&-q_1\\-q_2&q_1&q_0\\\end{matrix}\right]_{4\times3}\)

The non-linear equation of the state variable is presented in Eq. (3), which is specified in detail in Eq. (4).

\(\widehat{\dot{\mathbf{x}}}\left(t\right)=\mathbf{f}\left(\hat{\mathbf{x}}\left(t\right),\mathbf{u}\left(t\right)\right)+\mathbf{w}\left(t\right),\mathrm{\ \ }\mathbf{w}\left(t\right)~N\left(0,\mathbf{Q}\right)\)                                                                                                (3)

\(f\left(\hat{\mathbf{x}}(t),\mathbf{u}(t)\right)+\mathbf{w}\left(t_k\right)=\left[\begin{matrix}\dot{\hat{\mathbf{q}}}(t)\\ \dot{\hat{\mathbf{\boldsymbol{\omega}}}}(t)\\\dot{\hat{\mathbf{b}}}(t)\\\end{matrix}\right]+\mathbf{w}(t) = \left[\begin{matrix} {1 \over 2}\Omega(\hat{\boldsymbol{\omega}}_{LB}^B(t)) {\hat{\mathbf{q}}}(t) \\ \mathbf{I}^{-1} \left( \mathbf{u}(t)\times \mathbf{B}_{meas}^B-\hat{\boldsymbol{\omega}} (t)\times (\mathbf{I}\hat{\boldsymbol{\omega}} (t))\right ) \\ -{1 \over \tau} {\hat{\mathbf{b}}}(t)\\\end{matrix}\right] + \left[\begin{matrix} \mathbf{0} \\ \boldsymbol{\eta}_D(t) \\ \boldsymbol{\eta}_{bias}(t) \\\end{matrix}\right]\)                                                           (4)

In Eq. (4), \(\mathbf{u}(t)\) refers to the control input, \(\mathbf{B}_{meas}^B\) refers to the measurement of magnetic field in the body frame, and represents the Gaussian-distributed white noise. In addition, the space model with external disturbance considered gravity gradient torque and torque generated due to air friction and solar radiation wind as the covariance matrix (Q) as presented in Eq. (5).

\(\mathbf{w}\left(t_k\right)=\left[\begin{matrix}\mathbf{0}\\\mathbf{\eta}_D\left(t_k\right)\\\mathbf{\eta}_{bias}\left(t_k\right)\\ \end{matrix}\right], \mathbf{w}(t) \sim N(0, \mathbf{Q}), ~~~\mathbf{Q}=\left[\begin{matrix}\mathbf{0}_{4\times4}&\mathbf{0}_{4\times3}&\mathbf{0}_{4\times3}\\\mathbf{0}_{3\times4}&\left(\sigma_{GGT}^2+\sigma_{SRP}^2+\sigma_{AD}^2\right)\mathbf{I}_{3\times3}&\mathbf{0}_{3\times3}\\\mathbf{0}_{3\times4}&\mathbf{0}_{3\times3}&\left(\sigma_{RRW}\right)^2\cdot\mathbf{I}_{3\times3}\\\end{matrix}\right]          \)                                    (5)

\(\sigma_{RRW}:\mathrm{Gyroscope\ rate\ random\ walk\ noise} \\ \sigma_{GGT}:\mathrm{Worst\ case\ gravity\ gradient\ torque\ process\ noise} \\ \sigma_{SRP}:\mathrm{Worst\ case\ solar\ radiation\ pressure\ torque\ process\ noise} \\ \sigma_{AD}:\mathrm{\ Worst\ case\ aerodynamic\ torque\ process\ noise}\)

Linearization is required to use the EKF as presented in Eq. (6).

\(\dot{\mathbf{x}}(t)=f(\mathbf{x}(t),\mathbf{u}(t),\mathbf{w}(t))\rightarrow\dot{\mathbf{x}}=F\mathbf{x}+G\mathbf{u}+\Gamma\mathbf{w}\)                                                                           (6)

\(F=\frac{\partial f\left(\hat{\mathbf{x}},\mathbf{u}\right)}{\partial\hat{\mathbf{x}}}=\left[\begin{matrix}\frac{\partial\widehat{\dot{\mathbf{q}}}}{\partial\hat{\mathbf{q}}}&\frac{\partial\widehat{\dot{\mathbf{q}}}}{\partial\hat{\mathbf{\omega}}}&\frac{\partial\widehat{\dot{\mathbf{q}}}}{\partial\hat{\mathbf{b}}}\\\frac{\partial\widehat{\dot{\mathbf{\omega}}}}{\partial\hat{\mathbf{q}}}&\frac{\partial\widehat{\dot{\mathbf{\omega}}}}{\partial\hat{\mathbf{\omega}}}&\frac{\partial\widehat{\dot{\mathbf{\omega}}}}{\partial\hat{\mathbf{b}}}\\\frac{\partial\widehat{\dot{\mathbf{b}}}}{\partial\hat{\mathbf{q}}}&\frac{\partial\widehat{\dot{\mathbf{b}}}}{\partial\hat{\mathbf{\omega}}}&\frac{\partial\widehat{\dot{\mathbf{b}}}}{\partial\hat{\mathbf{b}}}\\\end{matrix}\right]=\left[\begin{matrix}\frac{1}{2}\mathbf{\Omega}({\hat{\mathbf{\omega}}}_{LB}^B)_{4\times4}&\frac{1}{2}\mathbf{\Xi}\left(\hat{\mathbf{q}}\right)_{4\times3}&\mathbf{0}_{4\times3}\\\mathbf{0}_{3\times4}&\begin{matrix}0&a{\hat{\omega}}_3&a{\hat{\omega}}_2\\b{\hat{\omega}}_3&0&b{\hat{\omega}}_1\\c{\hat{\omega}}_2&c{\hat{\omega}}_1&0\\\end{matrix}&\mathbf{0}_{3\times3}\\\mathbf{0}_{3\times4}&\mathbf{0}_{3\times3}&-\frac{1}{\tau}\mathbf{I}_{3\times3}\\\end{matrix}\right]\)                                                  (7)

\(\frac{1}{2}\mathbf{\Omega}({\hat{\mathbf{\omega}}}_{LB}^B)=\frac{1}{2}\mathbf{\Omega}\left(\hat{\mathbf{\omega}}-{\hat{R}}_L^B\mathbf{\omega}_{EL}^L\right)-\frac{1}{2}\mathbf{\Omega}\left(\frac{\partial{\hat{R}}_L^B}{\partial\hat{\mathbf{q}}}\mathbf{\omega}_{EL}^L\right)\hat{\mathbf{q}}\)                                                                          (8)

In Eq. (8), \( \frac{\partial R_L^B}{\partial\mathbf{q}}\) refers to a direct cosine matrix and \(R_L^B\) refers to a partial differential term with regard to the quaternion. In Eq. (10), the results that are developed by component can be seen. Here, the moment of inertia for each axis is induced by Eq. (11).

\(\frac{1}{2}\mathbf{\Omega}\left(\frac{\partial{\hat{R}}_L^B}{\partial\mathbf{q}}\mathbf{\omega}_{EL}^L\right)\mathbf{q}=\left[\begin{matrix}\frac{1}{2}\mathbf{\Omega}\left(\frac{\partial{\hat{R}}_L^B}{\partial q_0}\mathbf{\omega}_{EL}^L\right)\mathbf{q}&\cdots&\frac{1}{2}\mathbf{\Omega}\left(\frac{\partial{\hat{R}}_L^B}{\partial q_3}\mathbf{\omega}_{EL}^L\right)\mathbf{q}\\\end{matrix}\right]\)                                                                        (9)

\(\frac{\partial R_L^B}{\partial q_0}=2\left[\begin{matrix}q_0&q_3&-q_2\\-q_3&q_0&q_1\\q_2&-q_1&q_0\\\end{matrix}\right], \ \frac{\partial R_L^B}{\partial q_1}=2\left[\begin{matrix}q_1&q_2&q_3\\q_2&-q_1&q_0\\q_3&-q_0&-q_1\\\end{matrix}\right] \)                                                                                   
\( \frac{\partial R_L^B}{\partial q_2}=2\left[\begin{matrix}-q_2&q_1&-q_0\\q_1&q_2&q_3\\q_0&q_3&-q_2\\\end{matrix}\right],\mathrm{\ \ \ }\frac{\partial R_L^B}{\partial q_3}=2\left[\begin{matrix}-q_3&q_0&q_1\\-q_0&-q_3&q_2\\q_1&q_2&q_3\\\end{matrix}\right]\)                                                                               (10)

\(a=\frac{I_y-I_z}{I_x},b=\frac{I_z-I_x}{I_y},c=\frac{I_x-I_y}{I_z}\)                                                                                                (11)

Eq. (12) represents the input matrix (G), which is differentiated by the control input, and Eq. (13) represents the Gamma matrix.

\(G(t)=\frac{\partial f(\hat{\mathbf{x}}, \mathbf{u})}{\partial\mathbf{u}}=\left[\begin{matrix}\frac{\partial\widehat{\dot{\mathbf{q}}}}{\partial\mathbf{u}}&\frac{\partial\widehat{\dot{\mathbf{\omega}}}}{\partial\mathbf{u}}&\frac{\partial\widehat{\dot{\mathbf{b}}}}{\partial\mathbf{u}}\\\end{matrix}\right]^T ,\frac{\partial\widehat{\dot{\mathbf{q}}}}{\partial\mathbf{u}}=\mathbf{0}_{4\times3},\frac{\partial\widehat{\dot{\mathbf{\omega}}}}{\partial\mathbf{u}}=\left[\begin{matrix}0&\frac{B_z(t)}{I_x}&-\frac{B_y(t)}{I_x}\\-\frac{B_z(t)}{I_y}&0&\frac{B_x(t)}{I_y}\\\frac{B_y(t)}{I_z}&-\frac{B_x(t)}{I_z}&0\\\end{matrix}\right], \frac{\partial\widehat{\dot{\mathbf{b}}}}{\partial\mathbf{u}}=\mathbf{0}_{3\times3} \)                                                (12)

\(\Gamma=\frac{\partial f\left(\hat{\mathbf{x}},\mathbf{w}\right)}{\partial\mathbf{\eta}}=\left[\begin{matrix}\frac{\partial\widehat{\dot{\mathbf{q}}}}{\partial\mathbf{\eta}}&\frac{\partial\widehat{\dot{\mathbf{\omega}}}}{\partial\mathbf{\eta}}&\frac{\partial\widehat{\dot{\mathbf{b}}}}{\partial\mathbf{\eta}}\\\end{matrix}\right]^T=\left[\begin{matrix}\mathbf{0}_{4\times4}&\mathbf{0}_{4\times3}&\mathbf{0}_{4\times3}\\\mathbf{0}_{3\times3}&\mathbf{I}_{3\times3}&\mathbf{0}_{3\times3}\\\mathbf{0}_{3\times3}&\mathbf{0}_{3\times3}&\mathbf{I}_{3\times3}\\\end{matrix}\right]_{10\times9}\)                                                                          (13)

Eq. (14) exhibits the measurement equation, in which \(\mathbf{z}(t)\) refers to measurement vector, \(h(\hat{\mathbf{x}}(t))\) refers to non-linear model vector based on estimate. An error between them can be represented by \(\mathbf{y}(t)\) innovation vector.

\(\mathbf{y}(t)=\mathbf{z}(t)-h(\hat{\mathbf{x}}(t))\)                                                                                                    (14)

Table 1 presents measurement vector of estimation and control algorithm for eclipse and day in the space environment. Since the solar measurement cannot be used during eclipse, magnetic field vector \(\mathbf{b}_{meas}(t_k)\) and angular velocity system \(\mathbf{\omega}_{meas}(t_k)\) are used as measurements. In addition, a magnetorquer is used in the control so that magnetic field measurement cannot be used.

Table 1. Measurement vectors considering space environment.

  Day Eclipse
Estimation \(\mathbf{z}\left(t_k\right)=\left[\begin{matrix}\mathbf{b}_{meas}\left(t_k\right)\\\mathbf{s}_{meas}\left(t_k\right)\\\mathbf{\omega}_{meas}\left(t_k\right)\\\end{matrix}\right]\) \(\mathbf{z}\left(t_k\right)=\left[\begin{matrix}\mathbf{b}_{meas}\left(t_k\right)\\\mathbf{\omega}_{meas}\left(t_k\right)\\\end{matrix}\right]\)
Estimation & control \(\mathbf{z}\left(t_k\right)=\left[\begin{matrix}\mathbf{s}_{meas}\left(t_k\right)\\\mathbf{\omega}_{meas}\left(t_k\right)\\\end{matrix}\right]\) \(\mathbf{z}\left(t_k\right)=\mathbf{\omega}_{meas}\left(t_k\right)\)

 

In Eq. (15), the model vector \(h(\hat{\mathbf{x}}(t_k))\) uses the Earth magnetic field and sun model; and \(R_{ECEF}^{ECI}\) in Eq. (16) from the simplified coordinate conversion, and \({\widetilde{R}}_{ECI}^{Local}\) from the GPS measurements, the radial, in-track, and cross-track coordinate system is adopted using the ECI coordinate to calculate \({\widetilde{R}}_{ECI}^{Local}\), and using the estimated Euler angle, coordinate conversion is done into the final body-frame so that attitude estimation is performed with the method that calculates an error using the measured vector in the body-frame.

\(\mathbf{y}(t_k)=\mathbf{z}(t_k)-h(\hat{\mathbf{x}}(t_k)) \)                                                                                                                                                         
\( =\left[\begin{matrix}\mathbf{b}_{meas}^B(t_k)\\\mathbf{s}_{meas}^B(t_k)\\\mathbf{\omega}_{meas}^B(t_k)\\\end{matrix}\right]-\left[\begin{matrix}\mathbf{b}_{model}^B(t_k)\\\mathbf{s}_{model}^B(t_k)\\\hat{\mathbf{\omega}}(t_k)+\hat{\mathbf{b}}(t_k)\\\end{matrix}\right]=\left[\begin{matrix}\mathbf{b}_{meas}^B(t_k)\\\mathbf{s}_{meas}^B(t_k)\\\mathbf{\omega}_{meas}^B(t_k)\\\end{matrix}\right]-\left[\begin{matrix}{\hat{R}}_L^B{\widetilde{R}}_{ECI}^{Local}{\widetilde{R}}_{ECEF}^{ECI}R_{NED}^{ECEF}\mathbf{b}_{IGRF}^{NED}\\{\hat{R}}_L^B{\widetilde{R}}_{ECI}^{Local}\mathbf{s}_{JPL}^{ECI}\\\hat{\mathbf{\omega}}(t_k)+\hat{\mathbf{b}}(t_k)\\\end{matrix}\right]\)                                           (15)

\(\mathbf{b}_{IGRF}^{NED}=\frac{\mathbf{B}_{IGRF}^{NED}}{|\mathbf{B}_{IGRF}^{NED}|} \)                                                                                                                                                             
\( {\hat{R}}_L^B\mathrm{\ :\ by\ }\hat{\mathbf{x}}(t),\mathrm{estimated\ attitude} \)                                                                                                                              
\( {\widetilde{R}}_{ECI}^{Local}:\mathrm{\ by\ GPS\ meas.\ }(\bar{\mathbf{v}}_{ECEF},\bar{\mathbf{r}}_{ECEF} → {\widetilde{R}}_{ECEF}^{ECI} → {\widetilde{\mathbf{v}}}_{ECI},{\widetilde{\mathbf{r}}}_{ECI}) \)                                                                                
\( {\widetilde{R}}_{ECI}^{Local}=[\begin{matrix}I&-C&-R\\\end{matrix}]^T,~~~R={ {\widetilde{\mathbf{r}}}^{ECI} \over |{\widetilde{\mathbf{r}}}^{ECI}| },~~~C={ {\widetilde{\mathbf{r}}}^{ECI} \times {\widetilde{\mathbf{v}}}^{ECI} \over { |\widetilde{\mathbf{r}}}^{ECI} \times {\widetilde{\mathbf{v}}}^{ECI} | },~~~I=C \times R \)                                                                             
\( {\widetilde{R}}_{ECEF}^{ECI}:\mathrm{\ reduced model}\)                                                                                                                                         (16)

Eq. (17) refers to a linearized equation of the measurement equation, which can be linearized as presented in Eqs. (18) and (20).

\(\mathbf{y}(t)=\mathbf{z}(t)-h(\mathbf{x}(t))\rightarrow\mathbf{y}(t)=\mathbf{z}(t)-H\mathbf{x}(t)\)                                                                                 (17)

\(H=\frac{\partial h\left(\hat{\mathbf{x}}\left(t_k\right)\right)}{\partial\hat{\mathbf{x}}}=\left[\begin{matrix}\frac{\partial h\left(\hat{\mathbf{x}}\left(t_k\right)\right)}{\partial\hat{\mathbf{q}}}&\frac{\partial h\left(\hat{\mathbf{x}}\left(t_k\right)\right)}{\partial\hat{\mathbf{\omega}}}&\frac{\partial h\left(\hat{\mathbf{x}}\left(t_k\right)\right)}{\partial\hat{\mathbf{b}}}\\\end{matrix}\right]\)                                                                               (18)

\(\frac{\partial h\left(\hat{\mathbf{x}}\left(t_k\right)\right)}{\partial\hat{\mathbf{q}}}=\left[\begin{matrix}\frac{\partial R_{Local}^{Body}}{\partial q_0}R_{ECI}^{Local}\mathbf{R}_{NED}^{ECI}\frac{\mathbf{B}_{IGRF12}}{|\mathbf{B}_{IGRF12}|}&\cdots&\frac{\partial\mathbf{R}_{Local}^{Body}}{\partial q_3}\mathbf{R}_{ECI}^{Local}\mathbf{R}_{NED}^{ECI}\frac{\mathbf{B}_{IGRF12}}{|\mathbf{B}_{IGRF12}|}\\\frac{\partial\mathbf{R}_{Local}^{Body}}{\partial q_0}\mathbf{R}_{ECI}^{Local}\mathbf{R}\mathbf{s}_{sun}^{ECI}&\cdots&\frac{\partial\mathbf{R}_{Local}^{Body}}{\partial q_3}\mathbf{R}_{ECI}^{Local}\mathbf{R}\mathbf{s}_{sun}^{ECI}\\\mathbf{0}_{3\times1}&\cdots&\mathbf{0}_{3\times1}\\\end{matrix}\right]\)                                                            (19)

\(\frac{\partial h\left(\hat{\mathbf{x}}\left(t_k\right)\right)}{\partial\hat{\mathbf{\omega}}}=\left[\begin{matrix}\mathbf{0}_{3\times3}\\\mathbf{0}_{3\times3}\\\mathbf{I}_{3\times3}\\\end{matrix}\right]_{9\times3},\frac{\partial h\left(\hat{\mathbf{x}}\left(t_k\right)\right)}{\partial\hat{\mathbf{b}}}=\left[\begin{matrix}\mathbf{0}_{3\times3}\\\mathbf{0}_{3\times3}\\\mathbf{I}_{3\times3}\\\end{matrix}\right]_{9\times3}\)                                                                                    (20)

Considering the processor capacity in the OBC, a continuous system was discretized in the Van-loan algorithm during time update, and the system's state-transition matrix was considered as \(\mathrm{expm}(CT_s)\cong I+CT_s\) as a first order as presented in Eq. (21).

\(\widehat{\dot{\mathbf{x}}}(t)=F\hat{\mathbf{x}}(t)+\Gamma\mathbf{w}(t),\mathrm{\ \ }\mathbf{w}(t)~W(0,W) \)                                                                                            
\( \rightarrow\hat{\mathbf{x}}(t_{k+1})=\Phi_d\hat{\mathbf{x}}(t_k)+\mathbf{w}_d(t_k),\mathbf{w}_d \sim N(0,W_d) \)                                                                              
\( Q=\Gamma W\Gamma^T \)                                                                                                                                    
\( C=\left[\begin{matrix}-F&Q^T\\0&F^T\\\end{matrix}\right] \)                                                                                                                           
\( \mathrm{expm}(CT_s)=I+CT_s=\left[\begin{matrix}(I-F)T_s&QT_s\\0&(I+F^T)T_s\\\end{matrix}\right] \)                                                                      
\( \Phi_d=(I+F)T_s \)                                                                                                                              
\( W_d=\Phi_dQT_s^2\)                                                                                                                            (21)

The measure update and time update, which is a detailed algorithm of the final EKF can be expressed by Eqs. (22) and (23).

\(P^+=\left(I-KH\right)P^-\left(I-KH\right)^T+KRK^T \)                                                                                            
\({\hat{\mathbf{x}}}^+\left(t_k\right)={\hat{\mathbf{x}}}^-\left(t_k\right)+K\left[\mathbf{z}\left(t_k\right)-\mathbf{h}\left({\hat{\mathbf{x}}}^-\left(t_k\right)\right)\right]^{-1}\)                                                                                  (22)

\(\widehat{\dot{\mathbf{x}}}=F\hat{\mathbf{x}}+\Gamma\mathbf{w},\mathrm{\ \ }\mathbf{w} \sim W(0,W) \)                                                                                                                 
\( {\widehat{\dot{\mathbf{x}}}}^-\left(t_{k+1}\right)=f\left({\hat{\mathbf{x}}}^+\left(t_{k-1}\right),\mathbf{u}\left(t_{k-1}\right)\right) \)                                                                                                           
\( Q=\Gamma W\Gamma^T \)                                                                                                                                             
\( \Phi_d=I+F\Delta t,\mathrm{\ \ }W_d=\Phi Q\mathrm{\ \ }(\mathrm{Van-Loan,\ 1st\ order}) \)                                                                                
\( P^-=\Phi_dP^+{\Phi_d}^T+W_d \)                                                                                                                             
\({\hat{\mathbf{x}}}^-(t_{k+1})={\widehat{\dot{\mathbf{x}}}}^-(t_k)\Delta t+{\hat{\mathbf{x}}}^+(t_k)=f({\hat{\mathbf{x}}}^-(t_k))\Delta t+{\hat{\mathbf{x}}}^+(t_k) \)                                                                       (23)

2.3 Attitude Control Based on LQG

The quaternion state variable estimated in the EKF is converted into the Euler angle, and the Euler angle and angular velocity are used as the control state variable as presented in Eq. (24).

\({\hat{\mathbf{x}}}_c(t)=\left[\begin{matrix}\hat{\phi}&\hat{p}&\hat{\theta}&\hat{q}&\hat{\psi}&\hat{r}\\\end{matrix}\right]^T\)                                                                                                (24)

By using the LQG controller, the Kalman gain that satisfies the cost function in Eq. (25) is calculated to minimize the control state variable and input.

\(J=\frac{1}{2}\mathbf{x}(t_f)^TS\mathbf{x}(t_f)+\frac{1}{2}\int_{t_0}^{t_k}\left(\mathbf{x}(t_k)^TA\mathbf{x}(t_k)+\mathbf{u}(t_k)^TB\mathbf{u}(t_k)\right)dt\)                                                                          (25)

Furthermore, linearization can be done as shown in Eqs. (26) and (27) for LQG control.

\({\dot{\hat{\mathbf{x}}}}_c(t_k)=F_c{\hat{\mathbf{x}}}_c(t_k)+G_c(t_k)\mathbf{u}(t_k)\)                                                                                                  (26)

\(\left[\begin{matrix}\dot{\phi}\\\dot{p}\\\dot{\theta}\\\delta\dot{q}\\\dot{\psi}\\\dot{r}\\\end{matrix}\right]=\left[\begin{matrix}0&1&0&0&n&0\\\frac{3n^2(I_z-I_y)}{I_x}&0&0&0&0&\frac{n(I_z-I_y)}{I_x}\\0&0&0&1&0&0\\0&0&\frac{3n^2(I_z-I_x)}{I_y}&0&0&0\\-n&0&0&0&0&1\\0&\frac{n(I_y-I_x)}{I_z}&0&0&0&0\\\end{matrix}\right]\left[\begin{matrix}\phi\\p\\\theta\\\delta q\\\psi\\r\\\end{matrix}\right]+\left[\begin{matrix}0&0&0\\0&\frac{B_z}{I_x}&-\frac{B_y}{I_x}\\0&0&0\\-\frac{B_z}{I_y}&0&\frac{B_x}{I_y}\\0&0&0\\\frac{B_y}{I_z}&-\frac{B_x}{I_z}&0\\\end{matrix}\right]\left[\begin{matrix}\mu_x\\\mu_y\\\mu_z\\\end{matrix}\right]\)                                        (27)

Since the cube satellite is rotated along the orbit with an angular velocity of \(n\) (mean motion), it is designed to be controlled with \(\delta q=0\) by adopting a variable \(\delta q=q+n\) to make \(q\) to become \(-n\). In addition, because the cube satellite is controlled using the space magnetic field, G-matrix varies according to the attitude. Thus, the Kalman gain is calculated using the LQR function over the MATLAB in the PC as presented in Eq. (28), whereas the Kalman gain should be calculated in real time in the OBC. Thus, the Kalman gain was calculated using Potter’s method (Teukolsky et al. 2007) after obtaining the eigenvalue / eigenvector solution (Biswa 2003) via the algorithm to find the C language-based steady-state algebraic solution as presented in Eq. (29).

\(K_c(t_k)=lqr(F_c,G_c(t_k),Q_c,R_c)\)                                                                                    (28)

\({\dot{P}}_\infty=0,{F_c}^TP+PF_c+Q-PG_cR^{-1}{G_c}^TP_c=0 \)                                                                                     
\( \left[\begin{matrix}F_c&-G_c{R_c}^{-1}{G_c}^T\\-Q&-F^T\\\end{matrix}\right]\left[\begin{matrix}\widetilde{F}\\\widetilde{E}\\\end{matrix}\right]=\left[\begin{matrix}\widetilde{F}\\\widetilde{E}\\\end{matrix}\right]\Lambda,\mathrm{\ \ }H \overset{\Delta}{=} \left[\begin{matrix}F_c&-G_c{R_c}^{-1}{G_c}^T\\-Q&-{F_c}^T\\\end{matrix}\right] \)                                                                     
\( P(t_k)=\widetilde{E}{\widetilde{F}}^{-1} \)                                                                                                                     
\( K_c(t_k)={R_c}^{-1}G_c(t_k)^TP(t_k) \)                                                                                                           
\( \mathbf{u}(t_k)=-K_c(t_k)\mathbf{x}_c(t_k)\)                                                                                                           (29)

3. SINGLE-AXIS HILS EXPERIMENT

3.1 Single-Axis Hardware in the Loop Experiment Environment

As shown in Fig. 2, the algorithms of the actual satellite (flight model) and ground verification model (engineering model) estimate satellite attitudes, using the magnetic field model (IGRF-12) and sun model (JPL, DE405) that are reference vectors, with the measurements of the GPS. In the single-axis HILS verification experiment to verify the algorithms, compared to the left figure in Fig. 2, however, the reference vectors do not use the GPS, but set the initial origin (\(0°\)) as shown in the right figure of Fig. 2, in which a three sec. mean of the input is used.

f3.jpg 이미지
Fig. 3. Single-axis HIL experiment setup.

The important point that needs to be considered in the ground experiment in Fig. 3 is that since the magnetorquer, which is an actuator of SNUGLITE, is moved with very weak force, it cannot be controlled to the preferred attitude if the force due to a twist of fishing line and the force due to elasticity are larger than the input in the torquer that is controlled. Thus, the force due to a twist (\(\kappa\)) of a fishing line and elasticity (\(C\)) can be approximate by Eq. (30) first; and the dipole moment, which is the maximum input that can be produced by the torquer of the cube satellite, is \(\mathbf{\mu}=0.038~[Am^2]\). When this is experimented in the ground, since the size of the Earth's magnetic field is \(\mathbf{B}=0.5~[Gauss]\) and there is no component of the magnetic field in the Z-axis, the maximum torque that can be produced by the cube satellite can be calculated considering dip angle \(55°\) as presented in Eq. (32).

\(\tau=-(\kappa+C)\theta\)                                                                                                         (30)

\(\kappa:twisted{\ }\mathrm{constant,\ C:\ elastic\ modulus}\)

\(\mathbf{B}_{x,y}=0.5e^{-4}\cdot \cos{(}55°)=2.87e-5[T]\)                                                                                    (31)

\(\mathbf{\mu}\times\mathbf{B}_{x,y}=1.09e^{-6}[\mathrm{Nm}]\)                                                                                                 (32)

When the cube satellite is rotated at \(360°\) and 20% of the input is set, Eq. (33) proved that the control can be achieved using the input, which is larger than the external disturbance, if a fishing line whose cycle is about 30 min is selected.

\(\kappa+C=\frac{(1.09e^{-6})}{2\pi*5}=\mathrm{3.4696}e^{-8}\ [\mathrm{Nm}] \)                                                                                            
\( T=2\pi\sqrt{\frac{I}{(\kappa+C)}}=2\pi\sqrt{\frac{\mathrm{0.0028}}{\mathrm{3.4696}e^{-8}}}=1780\ [sec]≅33 [\min] \)                                                                            (33)

Next, the Engineering Model (EM) was manufactured and A3200 of Gomspace was used as the OBC as shown in Fig. 4.

f4.jpg 이미지
Fig. 4. Signal block diagram of engineering model (EM) cubesat.

3.2 Single-Axis Hardware in the Loop Experiment Result

3.2.1 Attitude Estimation Result

The single-axis HILS verification experiment in the yaw direction was conducted with regard to attitude estimation and control algorithm of the cube satellite. Fig. 5 shows that when the cube satellite is rotated one turn in the yaw direction, the estimation error is RMS \(1.6°\) at each axis on average, and can differ up to \(4.0°\), which can also be seen by referring to Table 2. Compared to the requirement conditions in Table 3, it is within \(5°\) which satisfies the performance of estimation error.

f5.jpg 이미지
Fig. 5. Estimation error of Euler angle.

Table 2. Estimation error of Euler angle.

  Roll angle error (°) Pitch angle error (°) Yaw angle error (°)
RMS
Max
1.5
2.5
1.6
3.4
1.7
4.0

 

Table 3. Estimation performance of yaw angle.

 

  RMS angle error (°) MAX angle error (°) Requirement (°)
Estimation error 2.7 1.6 < 5.0

 

3.2.2 Attitude Estimation and Control Result

The attitude estimation and control results of the single-axis cube satellite are the results of control that is performed with regard to \(\psi_c=0°\) and \(\psi_c=30°\) in the yaw direction using the LQG algorithm based on the estimation performance in Section 3.2.1. \(\psi_c\) in Figs. 6 and 7 refers to the control goal, \(\psi_{est}\) refers to the estimated attitude result, and \(\psi_{ref}\) is the actual yaw attitude value acquired through the image. Fig. 7 shows that when the initial value is \(\psi_0=35°\) and the control goal is \(\psi_c=0°\), the result is converged after 200 sec. The initial value in Fig. 7 is \(\psi_0=0°\), and the control goal is \(\psi_c=30°\). The control performance reveals about \(1.1°\) of RMS, and \(2.0°,3.0°\) of maximum values, which are very similar, as presented in Table 4. In addition, since it exhibited \(10°\) or smaller in the three-axis, which was the requirement, it was satisfied within \(5.77°(10°/\sqrt {3}=5.77°)\) on the basis of single-axis. Here, the result obtained through the images (10 sec interval after convergence) was used as the yaw reference value (green point in Figs. 6 and 7).

f6.jpg 이미지
Fig. 6. Estimation error of Euler angle (\(\psi_c=0°\)).

f7.jpg 이미지
Fig. 7. Estimation error of Euler angle (\(\psi_c=30°\)).

Table 4. Control performance of yaw angle.

Estimation & control (°) RMS angle error (°) MAX angle error (°) Requirement (°)
\( \psi_c =0 \)
\( \psi_c =30\)
1.10
1.12
2.0
3.0
< 5.77
< 5.77

 

4. CONCLUSIONS

This study compared the attitude determination and control algorithm, Attitude Determination and Control System (ADCS) of the cube satellite with the results via the SILS to verify the algorithm in the actual space environment through the PILS verification. It also verified the estimation performance and accuracy through the performance of the actual sensor via the single-axis HIL verification experiment in the ground. In addition, it verified the specifications of the sensors to be mounted in the actual cube satellite, and set their values to covariance values of the EKF and LQG filters. In order to obtain the measurement accurately without errors as much as possible, sensor error modeling and compensation were conducted. Afterward, the ADCS algorithm was verified in the ground through the HILS procedure. In particular, a single-axis HILS, which was advantageous in terms of practical viewpoints and cost-effectiveness, was used to verify the algorithm.

Finally, the attitude estimation and control results were numerically compared with the requirements, and the result showed that the estimation accuracy exhibited an error of up to 4.8° when point angle three-axis was considered, and the control accuracy proved that estimation and control can be estimated within up to 3°. These experimental results were obtained using the halogen lamp in the indoor. Thus, when actual sun measurements are used during space mission while the cube satellite rotates the orbit, the estimation accuracy is expected to improve.

References

  1. Biswa, D. 2003, Numerical Methods for Linear Control Systems (London: Academic Press)
  2. Jang, J.-Y. 2016, Attitude Determination and Control System for Low Earth Orbit CubeSat considering Operation Scenario, M.S. dissertation, Seoul National University.
  3. Jang, J.-Y., Kim Y.-D., No, H.-K., Yu, S.-K., Kim, O.-J., et al. 2016, Development and Verification of LQG based Attitude Determination and Control Algorithm of Cubesatellite "SNUGLITE" using GPS and Multiple Sensors, ION GNSS+ 2016, September 12-16, 2016, Oregon Convention Center, Portland, Oregon, pp.3731-3739
  4. Kim, O.-J., Jang, J.-Y., Yu, S.-K., Kang, S.-H., Choi, B.-K., et al. 2016, A Preliminary Design of SNUGLITE Cubesat Observing Space Weather and Earthquake Using GNSS Signals, KSAS 2016 Spring Conference, pp.310-311
  5. Kim, Y.-D. 2015, Attitude determination and control of cubesat using magnetic torquer and LQR controller, M.S. dissertation, Seoul National University
  6. Ni, S. & Zhang, C. 2011, Attitude Determination of Nano Satellite Based on Gyroscope, Sun Sensor and Magnetometer, Procedia Engineering ,15, 959-963. https://doi.org/10.1016/j.proeng.2011.08.177
  7. Ran, D., Sheng, T., Cao, L., Chen, X., & Zhao, Y. 2014, Attitude control system design and on-orbit performance analysis of nano-satellite - "Tian Tuo 1", Chinese Journal of Aeronautics, 27, 593-601. https://doi.org/10.1016/j.cja.2013.11.001
  8. Schwartz, J. L., Peck, M. A., & Hall, C. D. 2003, Historical Review of Air-Bearing Spacecraft Simulators, Journal of Guidance Control and Dynamics, 26, 513-522. https://doi.org/10.2514/2.5085
  9. Teukolsky, S. A., Vetterling, W. T., & Flannery, B. P. 2007, Numerical Recipes in C: The Art of Scientific Computing, 3rd ed. (Cambridge: Cambridge University Press), pp.590-596
  10. Ure, N. K., Kaya, Y. B., & Inalhan, G. 2011, The Development of a Software and Hardware-in-The-Loop Test System for ITU-PSAT II Nano Satellite ADCS, Aerospace Conference, IEEE, 5-12 March 2011, Big Sky, MT, USA. https://doi.org/10.1109/AERO.2011.5747481