1 Introduction

Orientation estimation is applied from mobile robotics [1] to space exploration [2,3,4,5,6,7]. Most cyber-physical systems impose computational constraints, while striving for better accuracy, robustness, and energy-efficiency; thus, requiring compromises.

This work focuses on orientation estimation with Kalman Filters (KFs), motivated by aerospace applications [2,3,4,5,6,7] and exploits the physical model of a small satellite to improve sensor fusion. We will address the need for estimators with stationary error dynamics, which is essential to prepare CubeSat s for high-accuracy Earth observation missions.

We contribute to the development of efficient orientation estimation algorithms. Our goal is to reduce computational complexity while maintaining attitude stability. First, we use the conditional independence of the physical model to decompose attitude kinematics and dynamics estimation; thus, decreasing computational cost. Second, we introduce the virtual sensor paradigm to transform the nonlinear observation model of the attitude filter into a linear one. This way, a linear attitude filter can be used, further reducing the computational cost. We compare the proposed algorithm to a quaternionic filter [8] and show its robustness and superior error dynamics.

2 Related works

Wahba’s problem [9] describes the general attitude estimation objective as

$$\begin{aligned} \min _{{\textbf {A}}}\sum _{i=1}^{n} {w}_i \Vert {\textbf {b}}_i - A_{r,b}{} {\textbf {r}}_i\Vert ^2, \end{aligned}$$
(1)

where n stands for the number of observations, \({w}_i\) express measurement confidence, \({\textbf {b}}_i\) denote vectors in the measurement (body), whereas \({\textbf {r}}_i\) those in the reference frame. \(A_{r,b}\) maps the attitude from the reference to the body frame. Here the focus is on quaternion methods due to their computational efficiency, compare to, e.g., Euler angles [10].

The eigenproblem formulation of (1) offers diverse solutions by trading off efficiency and robustness [9, 11]. Among which, the Estimator of the Optimal Quaternion (ESOQ) [12] and Second Estimator of the Optimal Quaternion (ESOQ2) [13] are the most efficient [14, 15]. Moreover, ESOQ2 can be solved in closed-form for two observations [13], which we exploit in Sect. 3.2.

The KF [16] is widely used for estimating orientation—usually the nonlinear Unscented Kalman Filter (UKF) [17], which is superior to the Extended Kalman Filter (EKF) [18]. Exploiting dynamic model structure—e.g., conditional linearity or independence—reduces complexity [19] without approximations as in the EKF or the Multiple Quadrature Kalman Filter (MQKF) [20].

Whereas the Marginalized Square Root Quadrature Kalman Filter (MSQKF) [21] uses a linear KF to marginalize out linear states; nonlinear measurements make this filter inapplicable for orientation estimation (cf. Sect. 3.1). As our goal is to reduce computational cost, we do not consider using KFs for Riemannian manifolds [8], although they can accommodate quaternions.

Since attitude kinematics is time-variant (cf. Sect. 3.1), independence does not hold—as required for the Generalized Compressed Kalman Filter (GCKF) [22], so we rely on conditional independence (cf. Sect. 3.2). Our contributions are:

  1. 1.

    We utilize conditional independences in the spacecraft’s kinematic and dynamic models to decompose the estimation problem into two filters;

  2. 2.

    We transform the nonlinear observation model of the attitude filter into a linear one, reducing the computational cost of the algorithm; and

  3. 3.

    We provide empirical evidence based on numerical simulations to show the superiority of our method compared to the Quaternionic Additive Square Root Unscented Kalman Filter (QuAdSRUKF) [8], especially in terms of error dynamics and robustness to epistemic uncertainty.

3 Proposal

This section describes the physical spacecraft model, then introduces and analyzes a decomposed estimation method, exploiting the equations of angular motion. To accommodate nonlinear vector measurements in a linear KF, we propose the virtual sensor paradigm and reason about its reduced computational cost.

3.1 Equations of angular motion

The equations of angular motion describe attitude and angular rate evolution over time. We parametrize attitude with a quaternion due to its advantages (no singularity, computational efficiency) [10].

A quaternion q is an element of the quaternion group \({\mathbb {H}}\) and is composed of a tuple \({\textbf {q}} = \left( s, {\textbf {w}}\right) = \left( \cos \frac{\phi }{2}, {\textbf {t}}\sin \frac{\phi }{2} \right) ,\) where s denotes the scalar, w the vector part [10]. An equivalent representation uses the half angle \(\phi /2\) and a rotation axis \({\textbf {t}}\in \mathbb {R}^{3}\). In accordance with the literature [10], we assume unit quaternions.

The four coordinates of unit quaternions are linearly dependent (they form a Riemannian manifold) [8]. Since KFs are designed for Euclidean systems, their additive updates will produce off-manifold samples for quaternions, since Riemannian manifolds are not closed w.r.t. addition  [8]. Interestingly, H.M.T. Menegaz has shown [8] that simply normalizing q after filter updates generally suffices in practice, which we exploit in our filter implementation to reduce computational cost.

Rotating a vector \({\textbf {r}}\) by the quaternion q is nonlinear in q, expressed as \({\textbf {q}} {\otimes } \textbf{r}{\otimes }\bar{{\textbf {q}}},\) where \(\bar{{\textbf {q}}}\) is the conjugate quaternion. We propose the virtual sensor paradigm to include vector measurements in the linear KF without using this nonlinear operation (Sect. 3.2).

The merit of our proposal is that it utilizes the linearity of the attitude kinematics [10]:

$$\begin{aligned} \dot{{\textbf {q}}}&= \dfrac{1}{2} \left[ \begin{array}{cc} 0 &{} -\omega ^{T} \\ \omega &{}-\left[ \omega \times \right] \end{array}\right] {\textbf {q}}, \end{aligned}$$
(2)

where \(\omega\) is the angular velocity, \(\left[ \omega \times \right]\) the matrix of the cross product.

However, the dependence on \(\omega\) requires modeling the attitude dynamics as well, which is done with the Newton-Euler equation [10]

$$\begin{aligned} \dot{\omega }&= {{\textbf {J}}}^{-1} \left[ \tau \left( {\textbf {q}}\right) - \left[ \omega \times \right] \left( {{\textbf {J}}} + \left[ \omega \times \right] {} {\textbf {L}}\right) \right] \end{aligned}$$
(3)

where \(\tau\) is the resultant torque affecting the body; \({{\textbf {J}}}\) the inertia matrix, while \({\textbf {L}}\) stands for angular momentum (e.g., if reaction wheels are present). In practice, both equations are discretized with time index t.

3.2 Decomposed estimation

To prove that the discrete joint probability density estimation problem can be decomposed, the Markov property should hold [23], i.e., (for given states \(\mathcal {X}\) and observations \(\mathcal {Y}\))

$$\begin{aligned} \mathcal {X}_{t-1} \perp \mathcal {X}_{t+1} | \mathcal {X}_{t} \qquad \wedge \qquad \mathcal {Y}_{t} \perp \mathcal {X}_{t-1} | \mathcal {X}_{t}. \end{aligned}$$

In this setting, \(\mathcal {X} = \left\{ {\textbf {q}}, \omega \right\}\) and \(\mathcal {Y} = \left\{ \tilde{{\textbf {q}}}, \tilde{\omega }\right\} ,\) where the accent \(\tilde{\circ }\) denotes measurements.

For q and \(\omega\), it is not sufficient to condition only on \({\textbf {q}}_{t}\) or \({\omega }_{t}\), as \(\tau\) indirectly relates both (3). Moreover, there is also direct dependence between \({\omega }_{t}\) and \({\textbf {q}}_{t}\).

Nonetheless, additionally conditioning on \({\textbf {q}}_{t}\) and on \({\omega }_{t}\) solves the problem. This gives

$$\begin{aligned} {\omega }_{t-1} \perp {\omega }_{t+1} |\ {\omega }_{t}, {\textbf {q}}_{t} \qquad \wedge \qquad {\textbf {q}}_{t-1} \perp {\textbf {q}}_{t+1} |\ {\omega }_{t}, {\textbf {q}}_{t}, \end{aligned}$$

fulfilling the Markov property for states. For observations \({\omega }_{t}\) and \({\textbf {q}}_{t}\) are sufficient, too.

Exploiting the Markov property, we can factorize the joint state distribution over time:

$$\begin{aligned} p\!\left( {\omega }_{1}, {\textbf {q}}_{1}, \!\dots \!, {\omega }_{n}, {\textbf {q}}_{n}, \!\dots \!\right) = p\left( {\textbf {q}}_{1} \right) \! p\left( {\omega }_{1} \right) \!\prod _{i=2} \!p\!\left( {\textbf {q}}_{i} | {\omega }_{i-1}, {\textbf {q}}_{i-1} \right) \!p\!\left( {\omega }_{i} | {\omega }_{i-1}, {\textbf {q}}_{i-1} \right) \!. \end{aligned}$$
(4)

Thus, we can estimate q and \(\omega\) separately if we use the most recent estimates of both quantities.

3.3 The virtual sensor

The factorized distribution (4) can be estimated more efficiently than the joint distribution [24]. This is independent of whether a linear or nonlinear filter is used—i.e., deploying a linear filter could further reduce computational costs.

To use a linear filter, the measurements need to be linear in the filter states \(\omega\), q. However, this does not hold for all sensors on CubeSat s [2, 4]: gyroscope (\(\omega\)) and Star Tracker (ST) (q) measurements are linear, but magnetometer, and Sun sensor measurements are nonlinear in the states q, \(\omega\) (measuring the Earth’s magnetic field B and the Sun vector s, respectively). Namely, B and s need to be compared to a reference vector (as in (1)) to extract attitude information. This requires that the observed vectors are rotated into the reference frame, which is nonlinear in q.

The virtual sensor avoids this nonlinear operation via an intermediate step that extracts the attitude information from the vector observations B, s by solving Wahba’s problem (1). We use the computationally efficient ESOQ2 [13] algorithm, which has a closed-form solution for two vector observations (i.e., B and s). However, a different algorithm could have been chosen based on the requirements of the estimation problem. We group the measurements as:

$$\begin{aligned} {{\textbf {y}}}_{\textrm{KF}} = \left[ {{\textbf {q}}_{\textrm{ESOQ2}}}; {{\textbf {q}}_{\textrm{ESOQ2}}}\right] \qquad \wedge \qquad {{\textbf {y}}}_{\textrm{UKF}} = \tilde{\omega }, \end{aligned}$$

where the accent \(\tilde{\circ }\) denotes the measured values, B the magnetic field vector, s the Sun vector, ESOQ2 the virtual sensor, and \({{\textbf {q}}_{\textrm{ESOQ2}}} = \textrm{ESOQ2}\left( \tilde{{\textbf {B}}}, \tilde{{\textbf {s}}}\right)\). The subscripts ST and ESOQ2 denote the (virtual) sensor producing the quaternions, whereas the KF and UKF subscripts indicate which filter uses the particular measurements. The above formulation enables us to decompose the estimation into a nonlinear (for \(\omega\)) and a linear (for q) filter.

Fig. 1
figure 1

The filter architecture for spacecraft attitude estimation—in this particular case, the box Virtual sensor converts \(\tilde{{\textbf {B}}}, \tilde{{\textbf {s}}}\) into a quaternion by the ESOQ2 [13] algorithm. Note that by interchanging particular sensor measurements, this structure is applicable to other domains as well. Accents \(\tilde{\circ }\) and \(\hat{\circ }\) denote measured and estimated values, respectively.

The architecture is shown in Fig. 1, where the round-headed arrow denotes the time-variant parameters of the matrices of the KF (2). Input arrows (w.r.t. the boxes) denote measurements, while output arrows the predictions. It describes one filter step visually, namely:

  1. 1.

    Collect measurements \(\tilde{\omega }, \tilde{{\textbf {q}}}, \tilde{{\textbf {s}}}, \tilde{{\textbf {B}}}\) from the physical sensors.

  2. 2.

    Estimate \(\hat{\omega }\) from \(\tilde{\omega }\) with the UKF;

  3. 3.

    Convert \(\tilde{{\textbf {s}}}, \tilde{{\textbf {B}}}\) to \({{\textbf {q}}_{{ESOQ2}}}\) with the virtual sensor (e.g., ESOQ2); and

  4. 4.

    Estimate \(\hat{{\textbf {q}}}\) from \(\tilde{{\textbf {q}}}, {{\textbf {q}}_{\textrm{ESOQ2}}}, \tilde{\omega }\).

The proposed decomposition is independent of the application; only the measurements and the virtual sensor needs to be adapted. ESOQ2 requires a reference vector database (\({\textbf {r}}_i\) in (1)), which might be a bottleneck for other domains. On the other hand, the virtual sensor can influence robustness as the price for computational efficiency [14, 15]—we investigate the latter in Sect. 4 w.r.t. the angle between B and s.

3.4 Computational complexity

Table 1 Filter parameters

Computational complexity savings are achieved by: (1) decomposing the estimation of the \((N+L)\)-dimensional state vector \((N=\dim \omega , L = \dim {\textbf {q}})\) into two filters; and (2) using the virtual sensor to make the information content (i.e., an attitude quaternion) of the observations B, s linear in q, which admits a linear KF for estimating the attitude.

Using a nonlinear UKF for jointly estimating \(\omega\) and q is of \(\mathcal {O}\left( \left[ N+L\right] ^3\right)\), since the UKF has a cubic cost in the state dimensionality [25]. By factorizing the joint state distribution (cf. (4)), separate nonlinear filters can be used with a total cost of \(\mathcal {O}\left( N^3+L^3\right)\). Since the dynamics of \(\omega\) is nonlinear (3), it needs to be estimated with an UKF. However, since the gyroscopes measure \(\omega\) directly, this UKF will have a linear observation model.

On the other hand, the estimation of q can be made more efficient with the virtual sensor: since q has linear dynamics (2), if the corresponding observation model can be made linear, the attitude estimate can rely on a linear KF. This is achieved with the virtual sensor, which converts s and B into a quaternion—which is linear in the state q, so a linear KF with cost \(\mathcal {O}\left( L\right)\) can be used [25].

Together, the cost is \(\mathcal {O}\left( N^3+L\right)\), since the virtual sensor’s cost does not depend on the dimensionality of the filter’s state, adding \(\mathcal {O}\left( 1\right)\) [13]. The main advantage of the proposed method is that it relies on conditional independences to decompose the estimation problem into two filters; thus, it uses no approximations: it does not linearize the equations of angular motion as in the EKF [18], but solves Wahba’s problem with the virtual sensor to make the observation model linear.

4 Numerical experiments

This section describes the satellite model, estimation algorithms, control loop, environmental models, and the initial parameters considered for the numerical simulations, and discusses the results.

Fig. 2
figure 2

The component-wise attitude error for the proposed method and the QuAdSRUKF of [8] (\(\textrm{ref}\) subscript), showing the stationarity of the proposed filter’s error. The discontinuity is only an artifact of converting the quaternion into Euler angles, it is not present in the quaternion components

4.1 Experimental setup

Our numerical experiments model a 3U Earth observation CubeSat on a polar, Sun-Synchronous Orbit (SSO) with \(98.2^\circ\) inclination and \(10\ AM\) LTDN and we choose the initial conditions and all parameters based on a real CubeSat mission [26]. Our simulator (written in Python) constitutes the decomposed filter, the control loop, and the environmental models. The Earth’s magnetic field is described with the IGRF [27] model (we use the implementation in [28]), the gravitational field by the WGS84 [29] model, whereas satellite position is calculated with SGP4 [30], using TLE data as implemented in [31].

We initialized the attitude quaternion q to \(\left[ 1,0,0,0\right]\), the angular velocity \(\omega\) to the zero vector for both the proposed and reference filters, the attitude target for the control loop with longitude \(19.040236^\circ\) and latitude \(47.497913^\circ\) (i.e., the coordinates for Budapest). The initial angular velocity norm for the detumbling experiments was set to \(1.745\ s^{-1},\) and detumbling was considered successful if \(\Vert \omega \Vert <0.021\ s^{-1}\)—these parameters reflect a real CubeSat mission [26]. We use the satellite inertia matrix for a 3U CubeSat  [26] (the satellite mass was not required for the simulations)

$$\begin{aligned} \begin{pmatrix} {5.08}\cdot 10^{-2}&{} {6.54}\cdot 10^{-5}&{} {-1.68}\cdot 10^{-3}\\ {6.54}\cdot 10^{-5} &{} {5.62}\cdot 10^{-2} &{} {4.16}\cdot 10^{-4} \\ {-1.68}\cdot 10^{-3} &{} {4.16}\cdot 10^{-4} &{} {2.19}\cdot 10^{-2}. \end{pmatrix} \end{aligned}$$
(5)

The control system consists of two control laws. Detumbling control is used to to dissipate the rotational energy of the satellite after being ejected from the rocket and determines the control torque with the standard law [10] \(k_{\textrm{det}}\left( \omega \times {\textbf {B}}_0\right) \times {\textbf {B}}_0,\) where \({\textbf {B}}_0\) is normalized to unit length and \(k_{\textrm{det}}={8}\cdot 10^{-3}\) is a scalar coefficient—the analysis of [32] provides a formula for choosing this parameter. After the angular velocity of the CubeSat is reduced, we use the control law of [33] for tracking the target attitude. The control torque \({\tau _{h}}\) is based on the error quaternion \({\textbf {q}}_{err} = \bar{{\textbf {q}}}_{ref} {\otimes } {\textbf {q}}_{ref}\) (\(\bar{\circ }\) denotes the conjugate quaternion) as:

$$\begin{aligned} {\tau _{h}} = -{k_{\textrm{h}, {\textbf {q}}}}{} {\textbf {w}}_{err} -{{\textbf {K}}_{\textrm{h}, {\omega }}}\left( \omega - \omega _{ref}\right) , \end{aligned}$$
(6)

where \({\textbf {w}}_{err}\) denotes the vector part of \({\textbf {q}}_{err}\), \({k_{\textrm{h}, {\textbf {q}}}}\) is a scalar, while \({{\textbf {K}}_{\textrm{h}, {\omega }}}\) a diagonal matrix. We empirically selected \({{\textbf {K}}_{\textrm{h}, {\omega }}}= {8.5}\cdot 10^{-2}\times {{\textbf {I}}_{3}}\) and \({k_{\textrm{h}, {\textbf {q}}}}= {3}\cdot 10^{-3}\) and use a zero target angular velocity \(\omega _{ref}\).

4.2 Results

Fig. 3
figure 3

Comparing the norm of the attitude error (converted to Euler angles) when the inertia matrix is uncertain. The proposed method is more robust than the QuAdSRUKF of [8] (\(\textrm{ref}\) subscript), as the mean error is slightly less, but variance is significantly smaller for the former (a \(3\sigma\) interval is calculated over 30 runs)

We compared the attitude determination error of our decomposed filter to the quaternionic QuAdSRUKF of [8], and investigated the robustness of our proposal (Table 1). We assessed the effect of varying the ST sampling frequency (as reduced incoming energy might force the human operators who control the satellite from the Earth to reduce ST usage), epistemic uncertainty of the dynamic model via the inertia matrix (which can change due to the vibration during launch), and its sensitivity to the angle between B and s. We parametrize the attitude with a quaternion q, but we report attitude-related quantities in terms of Euler angles for simplicity.

Fig. 4
figure 4

The difference between the attitude determination error of the QuAdSRUKF of [8] and that of the proposed method. Negative values indicate that the proposed method is more sensitive to less frequent ST measurements. The orange lines stand for the median, the boxes spread from the lower to the upper quartile of the data, and the whiskers show the data range

First, we compare the attitude error in Fig. 2, converted to Euler angles \(\phi , \theta , \psi\) (the discontinuity in the plot is only an artifact of converting the quaternion into Euler angles, it is not present in the quaternion components—both algortihms had the same initial conditions). The proposed method has a time-invariant error dynamics, while the quaternionic filter’s error is time-variant (denoted by the \(\textrm{ref}\) subscript in the figures)—a crucial advantage for the proposed method, since high-resolution Earth observation missions require attitude stability. The error vector’s norm’s variance is slightly higher for the proposed method, but as the component-wise plot shows, it has a stationary error. We hypothesize that the reason for a slightly larger variance is coming from the ESOQ2 algorithm, the sensitivity of which is analyzed below.

To model epistemic uncertainty we perturbed the satellite’s inertia matrix: while ensuring positive definiteness, at the start of each simulation, we multiplied all diagonal elements with a random number uniformly drawn from \(\left[ 0.95;1.05\right]\), for off-diagonal elements, we used samples of \(10^{-6}\) magnitude. The Monte Carlo simulations (30 experiments) with perturbed inertia matrix show the superior performance of the proposed method. Both the error norm and the standard deviation were lower than the quaternionic filter’s values (Fig. 3).

Figure 4 shows the distribution of the attitude error difference between the proposed method and the quaternionic QuAdSRUKF [8] for different ST sampling times, simulating the realistic scenario when the CubeSat does not have enough incoming energy to use the ST frequently. When the ST sampling time is increased over \(500\ ms,\) the reference quaternionic filter [8] had a lower attitude error, until that point the proposed filter was superior. This shows a limitation of the proposed method compared to the QuAdSRUKF. Nonetheless, even for using the ST only every \(125\ s\), the median error is below \(0.005\ rad\), which can still be considered as an acceptable error, e.g., compared to [34,35,36].

Fig. 5
figure 5

Empirical validation of (7). The blue plot shows the error norm of the ESOQ2 algorithm, the orange plot that the proposed penalty captures the uncertainty of ESOQ2. All values are normalized for the figure to \(\left[ 0;1\right]\)

An (almost) parallel s and B can decrease the accuracy of ESOQ2. Indeed, calculating the norm and standard deviation of the error quaternion \((\Vert \Delta {{\textbf {q}}_{\textrm{ESOQ2}}}\Vert\), i.e., the error between the true attitude quaternion and the output of ESOQ2) yields \(0.0187\pm 0.0146\) when the angle between B and s is greater than \(10^\circ ,\) whereas \(0.138\pm 0.148\) for smaller angles. The blue line in Fig. 5 shows the norm of the error quaternion. The periodic spikes correspond to scenarios when s and B become (approximately) parallel. To confirm this, we fitted a nonlinear curve onto the spikes (shown in orange) that depends on the inner product of these two vector observations—i.e., Fig. 5 shows that we can capture the extreme variability (the spikes) in \((\Vert \Delta {{\textbf {q}}_{\textrm{ESOQ2}}}\Vert\) by a nonlinear function of the inner product of s and B. The proposed formula is:

$$\begin{aligned} {f}\!\left( {\theta _{{{\textbf {s}}}, {{\textbf {B}}}}}\right) \!&= \! {\left\{ \begin{array}{ll} \!0, \ \Vert {\textbf {q}}_{\textrm{ESOQ2}}\Vert \ge 1 \\ \!c\dfrac{\exp \!\left( {k}{\theta _{{{\textbf {s}}}, {{\textbf {B}}}}}\right) \!-\!1}{\exp \!\left( {k}\right) \!-\!1}\!,\!\ \textrm{otherwise;} \qquad \textrm{where}\quad {\theta _{{{\textbf {s}}}, {{\textbf {B}}}}} = \dfrac{\left| \langle {\textbf {s}}; {\textbf {B}} \rangle \right| }{\Vert {\textbf {s}}\Vert \Vert {\textbf {B}}\Vert } \\ \end{array}\right. } \end{aligned}$$
(7)

where, \(c=40\) and \({k}=90\) are empirically determined constants to ensure a low attitude error and \({f}\!\left( {\theta _{{{\textbf {s}}}, {{\textbf {B}}}}}\right) \in \left[ 0;c\right]\). The quantity \({f}\!\left( {\theta _{{{\textbf {s}}}, {{\textbf {B}}}}}\right)\) is used as a penalty affecting the diagonal elements of the observation covariance matrix \({\textbf {R}}\) of the linear KF for the output of the virtual sensor (\({{\textbf {q}}_{\textrm{ESOQ2}}}\)), i.e., \({{\textbf {R}} = \textrm{diag}\left( {1}\cdot 10^{-3} \!\times \! {\textbf {I}}_{4}, {f}\!\left( {\theta _{{{\textbf {s}}}, {{\textbf {B}}}}}\right) +{1}\cdot 10^{-1} \!\times \! {\textbf {I}}_{4}\right) }\). We note that this strategy is specific for ESOQ2. We experimented with multiplying \({\theta _{{{\textbf {s}}}, {{\textbf {B}}}}}\) with \({(1-\Vert {{\textbf {q}}_{\textrm{ESOQ2}}}\Vert )},\) since our empirical observations suggested that smaller \(\Vert {{\textbf {q}}_{\textrm{ESOQ2}}}\Vert\) increases the error norm, but that did not change the value of \({f}\!\left( {\theta _{{{\textbf {s}}}, {{\textbf {B}}}}}\right)\) substantially.

We also report the attitude control error, stability, and the required time to detumble the spacecraft (i.e., when \(\Vert \omega \Vert <0.021\ s^{-1}\)) with the proposed filter in Table 2. Our numerical evaluation suggests competitive performance compared to attitude determination systems in current CubeSat s [34,35,36]. However, since our results are simulated, they should be validated in a physical model.

5 Conclusion

In this work, we studied attitude estimation for small spacecrafts. We analyzed the governing equations of angular motions and utilized conditional independences via the Markov property to decompose the attitude determination problem into two filters: one for estimating angular velocity, and one for estimating the attitude quaternion. Furthermore, we proposed the concept of a virtual sensor, with the help of which we transformed the nonlinear observation model of the attitude filter into a linear one. These two steps were essential for reducing computational cost: (1) the decomposition of the filter enabled the estimation of a factorized probability density; and (2) the virtual sensor made it possible to use a linear filter for attitude estimation.

Our analysis shows reduced computational cost, whereas our numerical experiments demonstrate a more robust filter w.r.t. epistemic uncertainty and better error dynamics than the nonlinear quaternionic QuAdSRUKF [8]. A possible bottleneck of our method is when ST measurements are less frequently available. Given these considerations, we believe that exploring the proposed methods in real-world CubeSat missions could potentially improve attitude determination in small spacecraft. Whereas the idea of the virtual sensor might be leveraged in other applications of attitude estimation.

Table 2 Performance metrics of the steady state