Next Article in Journal
Semi-Supervised Defect Detection Method with Data-Expanding Strategy for PCB Quality Inspection
Next Article in Special Issue
Monocular Pose Estimation of an Uncooperative Spacecraft Using Convexity Defect Features
Previous Article in Journal
Classification between Normal and Cancerous Human Urothelial Cells by Using Micro-Dimensional Electrochemical Impedance Spectroscopy Combined with Machine Learning
Previous Article in Special Issue
Optimal Tasking of Ground-Based Sensors for Space Situational Awareness Using Deep Reinforcement Learning
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Simplex Back Propagation Estimation Method for Out-of-Sequence Attitude Sensor Measurements

Department of Electrical & Computer Engineering, National University of Singapore, Singapore 117583, Singapore
*
Author to whom correspondence should be addressed.
Submission received: 30 September 2022 / Revised: 14 October 2022 / Accepted: 18 October 2022 / Published: 19 October 2022
(This article belongs to the Special Issue Attitude Estimation Based on Data Processing of Sensors)

Abstract

:
For a small satellite, the processor onboard the attitude determination and control system (ADCS) is required to monitor, communicate, and control all the sensors and actuators. In addition, the processor is required to consistently communicate with the satellite bus. Consequently, the processor is unable to ensure all the sensors and actuators will immediately respond to the data acquisition request, which leads to asynchronous data problems. The extended Kalman filter (EKF) is commonly used in the attitude determination process, but it assumes fully synchronous data. The asynchronous data problem would greatly degrade the attitude determination accuracy by EKF. To minimize the attitude estimation accuracy loss due to asynchronous data while ensuring a reasonable computational complexity for small satellite applications, this paper proposes the simplex-back-propagation Kalman filter (SBPKF). The proposed SBPKF incorporates the time delay, gyro instability, and navigation error into both the measurement and covariance estimation during the Kalman update process. The performance of SBPKF has been compared with EKF, modified adaptive EKF (MAEKF), and moving–covariance Kalman filter (MC-KF). Simulation results show that the attitude estimation error of SBPKF is at least 30% better than EKF and MC-KF. In addition, the SBPKF’s computational complexity is 17% lower than MAEKF and 29% lower than MC-KF.

1. Introduction

The development and manufacturing of the small satellite have been a focus in the industry over the past decades. It is reported that approximately 350 small satellites with a mass of less than 200 kg have been launched in 2021 [1]. The Satellite Technology And Research Centre (STAR) at the National University of Singapore is currently developing three satellites named Lumelite-1 to -3 for formation flying programs [2]. Each satellite has a wet mass of 18 kg. The Lumelite satellites are planned to be launched in 2023.
The Lumelite satellite bus system primarily consists of the attitude determination and control subsystem (ADCS), the onboard computer (OBC) system, the electrical power system (EPS), and the communication interface module (CIM). Each of these subsystems is required to continuously monitor its electrical status, communicate with the sensor or actuator that connects to the subsystem, and communicate with OBC. For example, the ADCS’s digital signal processor (DSP) is required to ensure a stable power supply to all sensors, and have no over-current drawn by any actuator, while continuously requesting data from the sensor and sending a command to the actuator at a fixed sampling interval. Due to the reason that each sensor requires a certain processing time upon receiving the request, and the DSP is processing other tasks concurrently the updated data from each sensor and actuator would be received at different time instances, which results in unsynchronized-sensor and actuator information.
Estimation algorithms, such as the extended Kalman filter (EKF) [3], Unscented Kalman filter (UKF) [4,5], Cubature Kalman filter (CKF) [6] and particle filter [7], are commonly used in the attitude determination process. In [8,9], the constraint condition of the quaternion is incorporated into the Kalman gain matrix computation. In [10], a fixed EKF gain method was introduced to lower the nanosatellite’s computational cost. In this case, the KF directly selects the respective gain matrix based on the attitude control mode of the satellite. On the other hand, [11] introduces the square root-based UKF (SRUKF) algorithm with fault detection and identification (FDI) capabilities. The FDI detects and isolates any outlier measurement to ensure the stable performance of the SRUKF algorithm. In addition, [12] introduces the dual vector discrete-time complementary filter (DV-DTCF) where each sensor has its corresponding estimated state vector. Each estimated state vector is updated with respect to its sensor reading; then, all the estimated states are fused in the z-domain via a given transfer function. While numerous estimation algorithms are available in the literature, the sensor data is often assumed to be fully synchronized without delay.
The unsynchronized sensor information, also known as the out-of-sequence measurement (OOSM), would degrade the estimation accuracy. As such, various algorithms have been developed to minimize the accuracy loss. The OOSM problem and associated Kalman filter-based solution were discussed in [13]. Subsequently, [14] presented the algorithm for OOSM-based multi-sensor multi-target application. In [15], the time measurement errors, due to the signal’s traveling time between transmitter and receiver, as well as processing time, have been taken into account when deriving the measurement model for the EKF process. The OOSM-based UKF was implemented in [16] while the PF algorithm was implemented in [17]. Both OOSM-based UKF and PF algorithms are capable of achieving higher estimation accuracy, but these algorithms generally have higher computational costs [18,19]. The weighted measurement fusion method was introduced in [20], with the scalar weight computed based on the distance between the transmitter and receiver. While these algorithms have been developed for unsynchronized sensor data applications, they are primarily developed for target tracking (or positioning) and not for satellite attitude determination applications.
The predictor–observer method was introduced in [21] for attitude estimation with delayed measurements. Its results show that it is capable of converging the attitude estimation error while the EKF experiences error divergence due to the existence of a large sensor delay. The modified adaptive EKF (MAEKF) was proposed in [22] by fusing the N-step of delay measurements and state transition matrices. The MAEKF has much higher estimation accuracy than the re-iterated EKF. However, the methods in [21,22] require additional memory to store N-step delayed measurements. In [23], the moving–covariance Kalman filter (MC-KF), which uses an additional smoothing process to improve the estimation accuracy due to unsynchronized sensor data, has been proposed. It demonstrated the feasibility of orientation estimation, but it is only applied in a two-dimensional position with a one-dimensional angle estimation scenario.
This paper proposed the simplex-back-propagation Kalman filter (SBPKF) to improve the accuracy loss of EKF due to unsynchronized sensor data. The SBPKF utilizes the power series of an exponential matrix to provide a simplification of delayed measurement vector estimation. In addition, the sun vector and magnetometer measurement covariances are formulated with the consideration of additional measurement error due to gyro noise, gyro bias in-stability, and global positioning system (GPS) error. Furthermore, this paper presents the derivation of MC-KF for quaternion and gyro bias estimation. The estimation accuracy of the proposed SBPKF has been benchmarked with EKF, MAEKF [22], and MC-KF in terms of the sensor delay period. The computational complexity of SBPKF, EKF, MAEKF, and MC-KF has also been compared in terms of the total number of multiplications per iteration process.
The paper is organized as follows. Section 2 discusses the ADCS DSP task process. Section 3 presents the standard EKF derivation, and Section 4 presents the MC-KF algorithm. The proposed SBPKF is presented in Section 5. Section 6 presents the simulation and results. Finally, Section 7 concludes the paper.

2. Tasks of Attitude Determination and Control System

Figure 1 illustrates the input and output (I/O) of ADCS between sensors, actuators, satellite bus systems, memory, payload, and DSP. Three Universal Asynchronous Receiver/Transmitter (UART) interfaces are used for the communication between DSP and magnetometer, communication between DSP and GPS receiver, and ADCS debugging purposes. The GPS receiver also directly provides a 1 pulse-per-second (1PPS) signal to DSP via a dedicated interface. The DSP communicates with the satellite bus system via a Controller Area Network (CAN) interface. The additional CAN interface is used for propulsion system communication purposes. The DSP controls the magnetic torquer via pulse-width modulation (PWM) interface, while it receives the coarse sun sensor data via an analog-to-digital converter (ADC) I/O. Lastly, the DSP communicates with a fine sun sensor and reaction wheel via RS-485 and RS-232 interfaces, respectively.
The I/O diagram in Figure 1 indicates that the DSP is required to perform various tasks to ensure the stability of the satellite. Furthermore, Table 1 indicates the sampling period of each task that must be handled by the DSP. During the early phase of firmware development and testing, it had been noticed that the sensor data acquisition process requires at least 55 milliseconds to 75 milliseconds (represented by t S , r and t B , r in Figure 2) per cycle. As shown in Figure 2, both the sun sensor and magnetometer require a certain time to respond to the request sent by DSP ( t S , r and t B , r , respectively) when the sensor task is initiated. For the ideal scenario, t S , r and t B , r shall be less than 5 milliseconds. It is noted that the test process only involves both ADC tasks and sensor tasks. It is expected that the sensor data acquisition process requires much longer time in the full firmware implementation.
In Figure 2, the attitude determination (AD) task and sensor task are performed at different frequencies. In addition to the delay in the sensor data acquisition process, the asynchronization issue between sensor data and the AD task (or δ t S by sun sensor and δ t B by magnetometer, respectively) would degrade the overall attitude determination accuracy. Thus, an algorithm to minimize the accuracy degradation due to the sensor data synchronization issue is required. As previously mentioned, the sun sensor or magnetometer measurement will only be considered as a delayed measurement if either δ t S or δ t B . is more than five milliseconds. The five milliseconds is the expected response time of the sensor under the ideal operation scenario.

3. Extended Kalman Filter

The small satellite is typically equipped with sun sensors, magnetic torquers, and microelectromechanical systems (MEMS) based inertial measurement unit (IMU). The MEMS IMU device includes both gyroscope and magnetometer sensors. The output of the MEMS IMU gyroscope is given by [24]
ω ˜ k = ω k + β + η g + η β
where overhead notation of “ . ˜ ” denotes measurement, ω ˜ k denotes the measured three-axis body rate, ω k denotes the truth three-axis body rate, η g denotes the output noise of the gyroscope, β denotes the truth gyroscope bias, and η β denotes the gyroscope bias due to the angular random walk and bias instability.
The general EKF process consists of gain matrix computation, estimated state and covariance update, and estimated state and covariance propagation. For EKF-based attitude determination, the objective is to estimate both the satellite’s attitude (or quaternion) and gyroscope bias. Thus, the estimated state vector is x ^ k = ϱ ^ k T β ^ T . The ϱ k is the vector component of the quaternion vector, q , such that [25]
q ^ k = ϱ ^ k T q ^ 4 , k
where the overhead notation of “ . ^ ” denotes the estimated vue, and q ^ 4 , k is the scalar of the quaternion vector with q ^ 4 , k = 1 ϱ ^ k T ϱ ^ k .
Given a pair of measurement vectors from sensors, and their corresponding estimated measurement vector, both q ^ k and β ^ are updated via the following process [25]
q ^ k + = q ^ k + 0.5 Ξ q ^ k δ ϱ ^ β ^ + = β ^ + δ β ^
where Ξ q k is defined in [25] and
δ ϱ ^ k T δ β ^ T = K y ˜ y ^ k
In (4), y y S T y B T T , where the subscript “S” denotes the sun vector and subscript “B” denotes the earth’s magnetic field vector. In addition, the superscript “−” denotes pre-update, superscript “+” denotes post update, and K denotes the Kalman filter gain matrix [26]
K = P k H k T H k P k H k T + R k 1
where R k denotes measurement noise covariance and H k denotes the Jacobian matrix of measurement vectors. Moreover, the mth sensor component of the estimated measurement vector in (4) can be expressed as [25]
y ^ m = A q ^ k e ^ m
where A q ^ k denotes the estimated attitude matrix at time t k , and e ^ m (a unit vector) is the estimated mth sensor’s measurement in the earth center inertia (ECI) reference frame. It is noted that the derivation of e ^ S associated to y ^ S is detailed in [27], and e ^ B is provided in Appendix A and (31). In addition, H k in (5) is given as [26]
H k = y ^ S / ϱ y ^ S / β y ^ B / ϱ y ^ B / β
For standard EKF, y ^ S / ϱ , y ^ B / ϱ , y ^ S / β and y ^ B / β are defined as [28]
y ^ S / ϱ = y ^ S × y ^ B / ϱ = y ^ B × y ^ S / β = y ^ B / β = 0 3 × 3  
Here, a × is the cross-product matrix [25]. By assuming that there is no cross-correlation between the sun vector and the earth magnetic field vector, R k can be written as
R k = R S , k 0 0 R B , k
where R S , k is the covariance associated with the sun sensor, and R B , k is the covariance associated with the magnetometer.
In general, the measurement vector, b ˜ m output by the mth sensor in the satellite body reference frame always contains an error, with the standard deviation of ν m :
b ˜ m = b m + ν m
where b m denotes the truth measurement reading of the mth sensor. Furthermore, b ˜ m maybe not necessarily a unit vector (e.g., Earth’s magnetic field vector). Therefore, y ˜ m represents the normalized vector of b ˜ m such that y ˜ m = b ˜ m / b ˜ m , where . denotes the vector’s magnitude. Then, the general expression of R m , k in (9) with the consideration of vector normalization is given as [29]:
R m , k = R ¯ m , k + 1 2 t r a c e R ¯ m , k b ˜ m b ˜ m T b ˜ m 2
R ¯ m , k = b ˜ m × 2 b ˜ m 3 E v m v m T b ˜ m × 2 b ˜ m 3 T
with E . denotes expected value, t r a c e R ¯ m , k denotes the summation of diagonal elements of R ¯ m , k . In addition, the state error covariance update is given as [26]
P k + = I K H k P k
Using the following definition, ω ^ k = ω ˜ k β ^ , the nonlinear quaternion propagation model is given as [30]
q ˙ = 1 2 Ω ¯ ω ^ k q ^ k
where Ω ¯ ω ^ k is defined in [30]. Due to the nature of quaternion multiplication, the integration of (14) is often highly complex. Instead, the quaternion propagation can be simplified using the Nx-step summation model [31]:
q ^ k + 1 I 4 × 4   + n = 1 N x 1 n ! Ω ¯ n ω ˜ k Δ t k n q ^ k +
The state error covariance propagation model is given by [26]
P ˙ = F k P k + + P k + F k T + Q
where [25]
F k = ω ˜ k β ^ × I 3 × 3 0 0 Q = E η g η g T + E η β η β T
The standard EKF shows that the state vector update process in (3) to (5), and the Jacobian matrix in (8) do not consider the unsynchronized sensor data problem. On the other hand, the proposed SBPKF and MC-KF include the sensor data delay and its associated sensitivity matrix and error covariance in the measurement model estimation. The MC-KF algorithm is presented in the next Section.

4. Moving Covariance Kalman Filter

The presented MC-KF in this section is based on [23,32]. It has a similar estimation process as DV-DTCF in [12] but a different state vector fusion approach. Let us define the following time instance, t m = t k δ t m , where subscript “m” is a general representation of either sun sensor,“S” or magnetometer “B”. First, given the sun sensor and magnetometer data arrive at different time instances, there are two sets of state correction vector, Δ x ^ m , t m
Δ x ^ m , t m = K m y ˜ m y ^ m , t m = δ ϱ ^ m , t m T δ β ^ m , t m T
where K m is the Kalman filter gain matrix that is derived with respect to the sensitivity matrix of each sensor:
K m = P k H m , t m T H m , t m P k H m , t m T + R m , k 1
where R m , k is defined in (11).
From (18), two sets of updated state vectors, x ^ m ,   t m + (or x ^ S ,   t S + and x ^ B ,   t B + ) and two sets of state error covariances, P m ,   t m + (or P S ,   t S + and P B ,   t B + ) will be obtained by using a similar formulation in (3) and (13). Next, both x ^ S ,   t S + , P S ,   t S + and x ^ B ,   t B + , P B ,   t B + pairs are required to be synchronized and smoothed. First, let’s define the following time instance, t u based on the following sensor delay information
t u t k δ t S 5   ms   and   δ t B 5   ms t k δ t S δ t S δ t B t k δ t B δ t B δ t S
As presented in Figure 3, the delay of 5 ms is assumed to be the minimum time required by a sensor to instantly reply to the sensor data request by ADCS DSP. Then, the x ^ P ,   t p and P P ,   t p pair that has a lesser delay with respect to t k , are propagated to t u
x ^ P ,   t p + x ^ P ,   t u
P P ,   t p + P P ,   t u
For generalization purposes, the sensor data with a higher delay is labeled as wth sensor. Based on [23], we define the following matrices, P P / W and P P W
P P W = P P , t u K W H W T + P W ,   t u + K P , t u H P , t u T + 5 E 4 × diag P P , t u + P W ,   t u +
P P / W = P P , t u K W H W K P , t u H P , t u T
where K m , t u and H m , t u are Kalman filter gain and sensitivity (derivation see (7), (8), (33) and (34)) matrices at t u . To ensure the positive definite of P P W   matrix, we have
P P W * = P P W + 5 E 4 × diag P P , t u + P W ,   t u +
In (25), “diag(A)” denotes the matrix only contains the diagonal elements of matrix A. The purpose is to ensure the matrix P P W * is invertible. Then, the smoothed state vector is given as
x ^ t u + = x ^ P , t u + P P / W P P W * 1   δ x t u
where
δ x t u = x ^ W , t u + x ^ P , t u
The quaternion update corresponding to (26) is given in (3). On the other hand, the quaternion subtraction to compute δ x t u is given as follows:
q ^ W , t u + q ^ P , t u Ψ q ^ W , t u q ^ W , t u + ϱ P q P , 4
with Ψ q is defined in [25]. Finally, the covariance is smoothed as follows
P t u + = P P , t u P P / W P P W * 1 P P / W
Lastly, both state vectors, x ^ t u + and covariance, P t u + , are propagated to the next time step, x ^ k + 1 and P k + 1   via (15) and (16).

5. Simplex-Back-Propagation Kalman Filter

The proposed SBPKF uses the similar Kalman filter process as EKF, but with different measurement and covariance models. The SBPKF has taken the delay between sensor data acquisition time and Kalman sampling time, δ t m (or known as δ t S and δ t B in Figure 2). As such, the delayed measurement vector for both the sun sensor and magnetometer in (6) is rewritten as:
y m , t k δ t m = I 3 × 3   + n = 1 N y 1 n n ! ω ˜ k β ^ × δ t m n A q ^ k e ^ m
It is noted that the Earth’s magnetic field vector in the ECI reference frame, e B is computed based on the satellite position and velocity at t k δ t B
e B = A NED ECI B r t k δ t B , v t k δ t B
where A NED ECI denotes the transformation matrix of NED to ECI reference frame, and B = B θ B ϕ B r T denotes the Earth’s magnetic field vector with each component representing North, East, and Down direction, respectively. For simplicity, the derivation of A NED ECI will not be shown in this paper, but the associated algorithm and Matlab code are available in [33]. In addition, r t k δ t B and v t k δ t B can be approximated as
r t k δ t B = r t k + δ t B v t k μ r t k δ t B 2 2 r t k 3 v t k δ t B = v t k μ r t k δ t B 2 r t k 3
From (30), the measurement vector is in terms of both quaternion and gyro bias. Therefore, both y ^ S / β and y ^ B / β are no longer zero matrices. Instead, with the additional summation terms, (8) becomes
y ^ m / ϱ = I 3 × 3   + n = 1 N y 1 n n ! ω ˜ k β ^ × δ t m n y ^ m ×
y ^ m β = y ^ m × δ t m + δ t m 2 2 ω ˜ k β ^ × y ^ m × + ω ˜ k β ^ × y ^ m ×
The general expression of R m , k remains the same as in (11). However, (31) indicates the satellite positioning error contributes to the Earth’s magnetic field modeling error. In addition, both η g and η β contribute additional errors in (30). Therefore, both R ¯ S , k and R ¯ B , k , which were originally formulated in (12) have been modified to become:
R ¯ S , k = b ˜ S × 2 b ˜ S 3 E ν S ν S T + R ^ S , δ t S   b ˜ S × 2 b ˜ S 3 T R ¯ B , k = b ˜ B × 2 b ˜ B 3 E ν B ν B T + R ^ B , δ t B + σ B r t k δ t B   b ˜ B × 2 b ˜ B 3 T
where
R ^ m , δ t m = Λ m Q Λ m T + δ t m 4 4 t r a c e Q y ^ m y ^ m T Q + Q y ^ m y ^ m T + t r a c e Q y ^ m y ^ m T
Λ m y ^ m × δ t m δ t m 2 2 ω ˜ k β ^ × y ^ m × δ t m 2 2 ω ˜ k β ^ × y ^ m ×
It is noted that the term σ B r t k δ t B denotes additional error covariance due to the satellite position error:
σ B r t k δ t B = A NED ECI B h LLA h LLA r ECEF E η r η r T A NED ECI B h LLA h LLA r ECEF T
In (38), B / h LLA denotes the partial derivative of B r t k δ t B , v t k δ t B in (31) with respect to longitude, ϕ , latitude, θ and radius, r (or h LLA = θ ϕ r T ). In addition, h LLA / r ECEF denotes the partial derivative of conversion from position in the Earth-centered-Earth-fix (ECEF) reference frame to longitude, latitude, and radius. The formulation for B / h LLA is available in Appendix A, and the formulation for conversion of ECEF position to longitude, latitude, and radius is detailed in [34].
The overall process flow for SBPKF (and MC-KF/MAEKF) is presented in Figure 3. When the satellite exits from the eclipse, the first pair of sun and Earth magnetic field vectors will be input into the quaternion estimation (QUEST) algorithm [35] to provide an initial quaternion vector, with the assumption of fully synchronized measurement vectors. The quaternion output from QUEST also guarantees the stability of EKF and SBPKF algorithms as the EKF-based algorithm is often susceptible to initial condition error [36]. As discussed in Section II, the respective measurement will only be considered as a delayed measurement for the filtering process if δ t m > 5   ms . Thus, if both δ t S and δ t B are less than a given threshold (i.e 5 ms), standard EKF will be conducted. Otherwise, the delayed measurement vector in (30) will be computed. Once the measurement covariances are computed using (11), (35) to (37), the SBPKF updates the estimated states and state error covariance using the (3) and (13).

6. Simulation and Results

Monte Carlo simulations have been conducted to compare the quaternion and gyro bias estimation accuracy for the proposed SBPKF, EKF, MAEKF in [22], and MC-KF, with respect to sensor delay. The Monte Carlo simulation environment is illustrated in Figure 4. Three ADCS tasks are considered in the simulation, which are the sensor task, AD task, and AC task. The sensor task is simulated at a sampling rate of 200 ms, with selected sensor delays. The sensor delay to be range from 65 ms to 145 ms, with its standard deviation given in Table 2. The AC task simulates the truth quaternion vector that is corresponding to the satellite pointing profile in Figure 5. The AD task comprises the attitude determination algorithm, such as SBPKF, EKF, MAEKF, and MC-KF. During the eclipse period (or without sunlight), the satellite attitude control enters the momentum hold condition. The default attitude control of the satellite during the sunlight condition is the sun-pointing mode. The satellite performs nadir pointing when the angle between the nadir axis and sun vector in the satellite body frame is within the sun sensor’s half-cone field-of-view (or 60 degrees). In Figure 5, the satellite begins to perform nadir pointing 15 min after entering the sunlight condition, for approximately 35 min.
For each Monte Carlo simulation, the performance of SBPKF, EKF, MAEKF, and MC-KF are evaluated for one sunlight period (or approximately 60 min). The satellite orbital parameters are provided in Table 2. It is noted that the right ascension of ascending node, the argument of perigee, and the initial true anomaly are randomly generated in each Monte Carlo simulation.
The sensors and gyro noises, GPS accuracy, sensor, and EKF sampling rate are listed in Table 2. The sun sensor, GPS, gyro, and magnetometer noises are based on the commercial off-the-shelf product, with the consideration of noise density and sensitivity. In addition, the configuration of MAEKF is based on details provided in [22].

6.1. Accuracy Comparison

Figure 6 compares the quaternion and gyro bias estimation error between the SBPKF, EKF, MAEKF, and MC-KF with respect to the estimation results without the sensor delay scenario. The average quaternion error magnitude and gyro bias error magnitude for the zero sensor delay scenario is 0.145 degrees and 2.8 millidegrees, respectively. The quaternion error ratio, q = , and gyro bias error ratio, β = , in Figure 6 are given by:
q = = k M d sin 1 q k , d k M 0 sin 1 q k , 0 M 0 M d × 100 %
β = = k M d β k , d k M 0 β k , 0 M 0 M d × 100 %
where M d is the total number of samples for the delayed sensor scenario, M 0 is the total number of samples for no sensor delay scenario, q k is the quaternion error, and β k is gyro bias error at kth sample with subscript “d” representing delayed sensor, scenario, and the subscript “0” representing no sensor delay scenario, respectively.
Figure 6a shows that the SBPKF has the lowest quaternion error magnitude, followed by MAEKF. The SBPKF’s quaternion estimation error ratio is approximately 189% (or 0.274 degrees) when compared to the no-sensor-delay scenario. The MAEKF quaternion error ratio is approximately 200% (or 0.29 degrees). Figure 6a also shows that without the simplex-back-propagation method, the quaternion estimation error ratio of EKF is increased to 220–250% (or 0.319 to 0.363 degrees), and the quaternion estimation error ratio of MC-KF is increased to 250–300% (or 0.363 to 0.435 degrees).
Figure 6b shows that the EKF has the lowest gyro bias error magnitude. However, the gyro bias error magnitude difference between EKF and the SBPKF can be considered negligible as both are in the range of millidegrees (or approximately three millidegrees). On the other hand, the MAEKF gyro bias error is three times higher than the SBPKF, even though it has a similar quaternion estimation error as the SBPKF. The additional error that occurs in MAEKF could be due to the reason that the MAEKF assumes all sensor data received at the same time instance. However, in practice, each sensor has a different time delay.
Although the MC-KF is designed to compensate for the error due to data delay, the introduction of unknown gyro bias as the initial condition has greatly degraded the performance of the MC-KF. From Figure 6b, the results show that the MC-KF has a large gyro bias error ratio as compared to the SBPKF and EKF. The MC-KF’s gyro bias error is approximately five times higher than the scenario without data delay. The MC-KF uses one measurement vector to update each x ^ S ,   t S and x ^ B ,   t B (see (18) and (26)). However, the attitude determination process requires at least a pair of measurement vectors to effectively estimate the quaternion vector. Furthermore, the additional covariance update process in (29) causes the state error covariance to be underestimated in MC-KF. The study in [37] has shown that an additional covariance update process within an iteration without a proper smoothing procedure could degrade the estimation accuracy. Therefore, the results in Figure 6 show that MC-KF would require a more complex derivation and implementation to ensure a stable estimation performance.
On the other hand, the proposed SBPKF considers the time delay of sensor data, δ t m when estimating the measurement vector in (30). In addition, (35) to (38) consider the additional propagation error due to the measurement model used in (30). Thus, the underestimation of error covariance is avoided, and the estimation accuracy is improved.
Overall, the results in Figure 6 provide the ADCS performance guideline during the system design review stage. The expected quaternion estimation error increment from Figure 6 allows the evaluation if an additional sensor, such as a star tracker is required to meet the system design requirement. STAR centre is presently developing a 50 kg microsatellite with a star tracker for high-precision pointing applications. The applicability of SBPKF will be verified on the engineering model. Subsequently, its in-orbit attitude determination accuracy performance will be benchmarked with the quaternion computed by the star tracker.

6.2. Computational Cost

Table 3 compares the number of multiplications required by EKF, SBPKF, MAEKF, and MC-KF at each iteration. The number of multiplication required for matrix multiplication and an inverse matrix is based on the method in [20]. The MAEKF’s multiplication number is the average multiplication number per sampling step within one second. This is due to the reason that the number of available measurement pairs for MAEKF varies between 1 and 2 at each sampling step.
For the SBPKF, MAEKF, and MC-KF, we assume the scenario where δ t > 5   ms . Table 3 shows that the number of multiplications required by MC-KF and MAEKF is approximately two times higher than EKF. The number of multiplication required by SBPKF is 17% lesser than MAEKF and 29% lesser than MC-KF, respectively. Although the SBPKF requires 65% more multiplication compared to EKF, the quaternion estimation error is improved by 30 to 45% with a similar gyro bias estimation error. Thus, the SBPKF achieves a higher attitude estimation accuracy at an expense of higher computational complexity.

7. Conclusions

This paper presented the simplex-back-propagation Kalman filter (SBPKF) for delayed sensor data-based quaternion and gyro bias estimation. The estimated measurements are formulated with the consideration of sensor data’s time delay to improve the quaternion estimation accuracy. In addition, the noise covariance matrices are derived with the presence of navigation error, gyro bias, and gyro noises to prevent underestimating the estimation error. The detailed implementation of the moving–covariance Kalman filter (MC-KF) for quaternion estimation has been presented. Monte Carlo simulations have been conducted to compare the accuracy and computational complexity of the proposed SPBKF, extended Kalman filter (EKF), modified adaptive EKF (MAEKF), and MC-KF. The results show that the SBPKF average estimated quaternion error is at least 30% lower than both EKF and MC-KF. Although the MAEKF quaternion estimation error is slightly higher than the SBPKF, its gyroscope bias estimation error is three times higher than SBPKF. In addition, the SPBKF computational complexity is 17% better than MAEKF and 29% better than MC-KF.
For future work, the SPBKF will be evaluated using the engineering model of a 50 kg microsatellite. The impact of the digital signal processor’s 8-bit floating point on the overall SPBKF accuracy performance will also be investigated.

Author Contributions

Conceptualization, R.D.T. and A.S.; methodology, S.T.G.; formal analysis and resources, R.D.T. and M.S.C.T.; writing—original draft preparation, S.T.G.; review and editing, K.-S.L.; supervision, L.S.L.; funding acquisition, K.-S.L. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by National Research Foundation (NRF) Singapore, Office for Space Technology & Industry (OSTin) under the NUS Formation Flying Microsatellites Program with grant number S21-19009-STDP.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest. The funders had no role in the design of the study; in the collection, analyses, or interpretation of data; in the writing of the manuscript, or in the decision to publish the results.

Appendix A

This appendix provides an overview of the derivation of the Earth’s magnetic field and its associate partial derivative. From Appendix H in [38], the North–East–Down components of the Earth’s magnetic field vector (or B θ , B ϕ and B r ) are given as
B θ = n = 1 k a r n + 2 m = 0 n g n , m cos m ϕ + h n , m sin m ϕ P n , m θ c θ c B ϕ = 1 sin θ c n = 1 k a r n + 2 m = 0 n m g n , m sin m ϕ + h n , m cos m ϕ P n , m θ c B r = n = 1 k a r n + 2 n + 1 m = 0 n g n , m cos m ϕ + h n , m sin m ϕ P n , m θ c
Here, θ c is the geocentric co-latitude such that
θ c = 90 θ
where θ is the geodetic latitude.
The partial derivate of each component in B , with respect to the North–East–Down direction (or known as θ , ϕ , and r, respectively) are given as
B θ θ = n = 1 k a r n + 2 m = 0 n g n , m cos m ϕ + h n , m sin m ϕ 2 P n , m θ c θ c 2 B ϕ θ = 1 sin θ c n = 1 k a r n + 2 m = 0 n m g n , m sin m ϕ + h n , m cos m ϕ P n , m θ c θ c + cos θ c sin 2 θ c n = 1 k a r n + 2 m = 0 n m g n , m sin m ϕ + h n , m cos m ϕ P n , m θ c B r ϕ = n = 1 k a r n + 2 n + 1 m = 0 n m g n , m sin m ϕ + h n , m cos m ϕ P n , m θ c
B r θ = n = 1 k a r n + 2 n + 1 m = 0 n g n , m cos m ϕ + h n , m sin m ϕ P n , m θ c θ c B θ ϕ = n = 1 k a r n + 2 m = 0 n m g n , m sin m ϕ + h n , m cos m ϕ P n , m θ c θ c B ϕ ϕ = 1 sin θ c n = 1 k a r n + 2 m = 0 n m 2 g n , m cos m ϕ + h n , m sin m ϕ P n , m θ c
B θ r = n + 2 n = 1 k a n + 2 r n + 3 m = 0 n g n , m cos m ϕ + h n , m sin m ϕ P n , m θ c θ c B ϕ r = n + 2 sin θ c n = 1 k a n + 2 r n + 3 m = 0 n m g n , m sin m ϕ + h n , m cos m ϕ P n , m θ c B r r = n + 2 n = 1 k a n + 2 r n + 3 n + 1 m = 0 n g n , m cos m ϕ + h n , m sin m ϕ P n , m θ c
It is noted that based on (A2), the partial derivate of the Earth’s magnetic field with respect to geodetic latitude θ in (A3) to (A5) has been simplified based on the following definition
B θ B θ c θ c θ = B θ c
In addition, from Appendix H in [38], the Gauss function P n , m θ c are given as below:
P 0 , 0 θ c = 1
P n , n θ c = sin θ c P n 1 , n 1 θ c
P n , m θ c = cos θ c P n 1 , m θ c K P n , m P n 2 , m θ c
K P n , m n 1 2 m 2 2 n 1 2 n 3 if   n > 1 0 if   n = 1
The first and second order partial derivative with respect to θ c can be obtained via (A7) to (A9).

References

  1. BryceTech. Smallsats by the Numbers 2022; BryceTech: Alexandria, VA, USA, 2022; p. 35. Available online: https://www.brycetech.com/reports/report-documents/Bryce_Smallsats_2022.pdf (accessed on 7 February 2022).
  2. Tissera, M.S.C.; Low, K.S.; Goh, S.T. On-orbit Gyroscope Bias Compensation to Improve Satellite Attitude Control Performance. In Proceedings of the IEEE Aerospace Conference, Big Sky, MT, USA, 6–13 March 2021. [Google Scholar]
  3. Garcia, R.V.; Pardal, P.C.P.M.; Kuga, H.K.; Zanardi, M.C. Nonlinear filtering for sequential spacecraft attitude estimation with real data: Cubature Kalman Filter, Unscented Kalman Filter and Extended Kalman Filter. Adv. Space Res. 2019, 63, 1038–1050. [Google Scholar] [CrossRef]
  4. Zanetti, R.; DeMars, K.J. Fully Multiplicative Unscented Kalman Filter for Attitude Estimation. J.Guid.Control Dyn. 2018, 41, 1183–1189. [Google Scholar] [CrossRef]
  5. Crassdis, J.L.; Markley, F.L. Unscented Filtering for Spacecraft Attitude Estimation. J.Guid.Control Dyn. 2003, 26, 536–542. [Google Scholar] [CrossRef] [Green Version]
  6. QIU, Z.; QIAN, H.; WANG, G. Adaptive robust cubature Kalman filtering for satellite attitude estimation. Chin. J. Aeronaut. 2018, 31, 806–819. [Google Scholar] [CrossRef]
  7. Cheng, Y.; Crassidis, J.L. Particle Filtering for Attitude Estimation Using a Minimal Local-Error Representation. J.Guid.Control Dyn. 2010, 33, 1305–1310. [Google Scholar] [CrossRef]
  8. Zanetti, R.; Majji, M.; Bishop, R.H.; Mortari, D. Norm-Constrained Kalman Filtering. J.Guid.Control Dyn. 2009, 32, 1458–1465. [Google Scholar] [CrossRef]
  9. Forbes, J.R.; Ruiter, A.H.J.d.; Zlotnik, D.E. Continuous-time norm-constrained Kalman filtering. Automatica 2014, 50, 2546–2554. [Google Scholar] [CrossRef]
  10. Pham, M.D.; Low, K.S.; Goh, S.T.; Chen, S. Gain-scheduled extended kalman filter for nanosatellite attitude determination system. IEEE Trans. Aerosp. Electron. Syst. 2015, 51, 1017–1028. [Google Scholar] [CrossRef]
  11. Pourtakdoust, S.H.; Mehrjardi, M.F.; Hajkarim, M.H. Attitude estimation and control based on modified unscented Kalman filter for gyro-less satellite with faulty sensors. Acta Astronaut. 2022, 191, 134–147. [Google Scholar] [CrossRef]
  12. Li, X.; Xu, Q.; Tang, Y.; Xu, C.; Hu, C.; Niu, J. Discrete-time complementary filter for attitude estimation based on MARG sensor. Meas. Sci. Technol. 2022, 33, 10. [Google Scholar] [CrossRef]
  13. Bar-Shalom, Y. Update with out-of-sequence measurements in tracking: Exact solution. IEEE Trans. Aerosp. Electron. Syst. 2002, 8, 769–777. [Google Scholar] [CrossRef]
  14. Mallick, M.; Krant, J.; Bar-Shalom, Y. Multi-sensor multi-target tracking using out-of-sequence measurements. In Proceedings of the Fifth International Conference on Information Fusion, Annapolis, MD, USA, 8–11 July 2002. [Google Scholar]
  15. Fosbury, A.M. Estimation with multitemporal measurements. J.Guid.Control Dyn. 2010, 33, 1518–1526. [Google Scholar] [CrossRef]
  16. Chen, J.; Li, J.; Gao, X. Single-step-lag OOSM algorithm based on unscented transformation. Sci. China Inf. Sci. 2011, 54, 664–673. [Google Scholar] [CrossRef] [Green Version]
  17. Mallick, M.; Marrs, A. Comparison of the KF and particle filter based out-of-sequence measurement filtering algorithms. In Proceedings of the Sixth International Conference of Information Fusion, QLD, Australia, 8–11 July 2003. [Google Scholar]
  18. Rozas, H.; Jaramillo, F.; Perez, A.; Jimenez, D.; Orchard, M.E.; Medjaher, K. A method for the reduction of the computational cost associated with the implementation of particle-filter-based failure prognostic algorithms. Mech. Syst. Signal Process. 2020, 135, 14. [Google Scholar] [CrossRef]
  19. Tang, C.; Dou, L. An Improved Game Theory-Based Cooperative Localization Algorithm for Eliminating the Conflicting Information of Multi-Sensors. Sensors 2020, 20, 5579. [Google Scholar] [CrossRef] [PubMed]
  20. Goh, S.T.; Abdelkhalik, O.; Zekavat, S.A.R. A Weighted Measurement Fusion Kalman Filter implementation for UAV navigation. Aerosp. Sci. Technol. 2013, 28, 315–323. [Google Scholar] [CrossRef]
  21. Khosravian, A.; Trumpf, J.; Mahony, R.; Hamel, T. Recursive attitude estimation in the presence of multi-rate and multi-delay vector measurements. In Proceedings of the American Control Conference (ACC), Chicago, IL, USA, 1–3 July 2015. [Google Scholar]
  22. Fei, Y.; Meng, T.; Jin, Z. Nano satellite attitude determination with randomly delayed measurements. Acta Astronaut. 2021, 185, 319–332. [Google Scholar] [CrossRef]
  23. Pornsarayouth, S.; Wongsaisuwan, M. Sensor fusion of delay and non-delay signal using Kalman Filter with moving covariance. In Proceedings of the IEEE International Conference on Robotics and Biomimetics, Bangkok, Thailand, 22–25 February 2009. [Google Scholar]
  24. Yuan, D.; Ma, X.; Liu, Y.; Shang, Z.; Yan, S. Statistical Modeling of Random Walk Errors for Triaxial Rate Gyros. IEEE Trans. Instrum. Meas. 2016, 65, 286–296. [Google Scholar] [CrossRef]
  25. Crassidis, J.L.; Junkins, J.L. Optimal Estimation of Dynamic Systems; Chapman & Hall/CRC: Boca Raton, FL, USA, 2004; pp. 152–154, 267, 421–424. [Google Scholar]
  26. Goh, S.T.; Zekavat, S.A.R.; Abdelkhalik, O. An Introduction to Kalman Filtering Implementation for Localization and Tracking Applications. In Handbook of Position Location: Theory, Practice, and Advances; Zekavat, S.A.R., Buehrer, R.M., Eds.; Wiley-IEEE Press: Piscataway, NJ, USA, 2019; pp. 143–195. [Google Scholar]
  27. Office, G.P. Sun. In The Astronomical Almanac For The Year 2020; Riggins, M., Humphrey, J., Eds.; United States Naval Observatory (USNO)Nautical Almanac Office: Washington, DC, USA, 2020; p. C5. [Google Scholar]
  28. Baroni, L. Kalman filter for attitude determination of a CubeSat using low-cost sensors. Comput. Appl. Math. 2018, 37, 72–83. [Google Scholar] [CrossRef]
  29. Andrle, M.S.; Crassidis, J.L.; Linares, R.; Cheng, Y.; Hyun, B. Deterministic Relative Attitude Determination of Three-Vehicle Formation. J.Guid.Control Dyn. 2009, 32, 1077–1088. [Google Scholar] [CrossRef]
  30. Challa, M.S. Simultaneous estimation of attitude and Markov-modeled rate corrections of gyroless spacecraft. J.Guid.Control Dyn. 2017, 40, 2386–2392. [Google Scholar] [CrossRef]
  31. Casey, R.T.; Karpenko, M.; Curry, R.; Elkaim, G. Attitude Representation and Kinematic Propagation for Low-Cost UAVs. In Proceedings of the AIAA Guidance, Navigation, and Control (GNC) Conference, Boston, MA, USA, 19–22 August 2013; p. 25. [Google Scholar]
  32. Gao, J.B.; Harris, C.J. Some remarks on Kalman filters for the multisensor fusion. Inf. Fusion 2002, 3, 191–201. [Google Scholar] [CrossRef]
  33. Vallado, D.A. Coordinate and Time Systems. In Fundamentals of Astrodynamics and Applications, 3rd ed.; Microcosm Press: Hawthorne, CA, USA, 2007. [Google Scholar]
  34. Rönnbäck, S. Development of a INS/GPS navigation loop for an UAV. Master’s Thesis, Department of Computer Science and Electrical Engineering, Luleå University of Technology, Luleå, Sweden, 2000. [Google Scholar]
  35. SHUSTER, M.D.; OH, S.D. Three-axis attitude determination from vector observations. J. Guid. Control Dyn. 1981, 4, 70–77. [Google Scholar] [CrossRef]
  36. Wu, G.; Zhang, J.; Li, G.; Wang, L.; Yu, Q.; Guo, J. Identification method of nonlinear maneuver model for unmanned surface vehicle from sea trial data based on support vector machine. J. Mech. Sci. Technol. 2022, 36, 4257–4267. [Google Scholar] [CrossRef]
  37. Goh, S.T.; Abdelkhalik, O.; Zekavat, S.A.R. Constraint Estimation of Spacecraft Positions. J.Guid.Control. Dyn. 2012, 35, 387–397. [Google Scholar] [CrossRef]
  38. Plett, M. Magnetic Field Models. In Spacecraft Attitude Determination and Control; Wertz, J.R., Ed.; Springer: Dordrecht, The Netherlands, 1978; pp. 779–786. [Google Scholar]
Figure 1. Input and output of attitude determination and control system’s digital signal processor.
Figure 1. Input and output of attitude determination and control system’s digital signal processor.
Sensors 22 07970 g001
Figure 2. Timestamp of attitude determination task, sensor task, and response of sensor.
Figure 2. Timestamp of attitude determination task, sensor task, and response of sensor.
Sensors 22 07970 g002
Figure 3. Algorithm flow diagram for delayed sensor scenario.
Figure 3. Algorithm flow diagram for delayed sensor scenario.
Sensors 22 07970 g003
Figure 4. Process flow of sensor task, attitude determination (AD) task, and attitude control (AC) task for attitude determination Monte Carlo simulation.
Figure 4. Process flow of sensor task, attitude determination (AD) task, and attitude control (AC) task for attitude determination Monte Carlo simulation.
Sensors 22 07970 g004
Figure 5. Satellite attitude control condition for Monte Carlo simulation.
Figure 5. Satellite attitude control condition for Monte Carlo simulation.
Sensors 22 07970 g005
Figure 6. Estimation accuracy performance comparison with respect to zero-sensor delay scenario: (a) Magnitude of quaternion error, and (b) Magnitude of gyro bias error.
Figure 6. Estimation accuracy performance comparison with respect to zero-sensor delay scenario: (a) Magnitude of quaternion error, and (b) Magnitude of gyro bias error.
Sensors 22 07970 g006
Table 1. ADCS DSP task.
Table 1. ADCS DSP task.
Sampling PeriodTask
100 msADC Task
200 msSensor Task
250 msAD task
500 msHousekeeping Task
1000 msAC task
Table 2. Simulation Configuration.
Table 2. Simulation Configuration.
ParameterValueParameterValue
Semimajor axis6963.145 kmSun sensor noise, ν S 0.1   deg
Eccentricity0.0001Magnetometer noise, ν B 45   nT
Inclination10 degGyro noise, η g 0.135   deg
N x 3Gyro bias, β ± 0.2   deg / s
EKF sampling rate 4   Hz In-run bias stability, η β 4.8456   mdeg / hr
Sensor sampling rate 5   Hz Position Error, η r 15 m
Sensor Delay Standard Deviation5 ms
Table 3. Comparison of number of multiplications.
Table 3. Comparison of number of multiplications.
AlgorithmNumber of Multiplications
EKF4104
Proposed6774
MAEKF8066
MC-KF9406
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Goh, S.T.; Tissera, M.S.C.; Tan, R.D.; Srivastava, A.; Low, K.-S.; Lim, L.S. Simplex Back Propagation Estimation Method for Out-of-Sequence Attitude Sensor Measurements. Sensors 2022, 22, 7970. https://0-doi-org.brum.beds.ac.uk/10.3390/s22207970

AMA Style

Goh ST, Tissera MSC, Tan RD, Srivastava A, Low K-S, Lim LS. Simplex Back Propagation Estimation Method for Out-of-Sequence Attitude Sensor Measurements. Sensors. 2022; 22(20):7970. https://0-doi-org.brum.beds.ac.uk/10.3390/s22207970

Chicago/Turabian Style

Goh, Shu Ting, M. S. C. Tissera, RongDe Darius Tan, Ankit Srivastava, Kay-Soon Low, and Lip San Lim. 2022. "Simplex Back Propagation Estimation Method for Out-of-Sequence Attitude Sensor Measurements" Sensors 22, no. 20: 7970. https://0-doi-org.brum.beds.ac.uk/10.3390/s22207970

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop