You are on page 1of 6

JOURNAL OF GUIDANCE, CONTROL, AND DYNAMICS

Vol. 37, No. 6, November–December 2014

Engineering Notes
Norm-Constrained Consider Kalman filter (CKF) accounts for uncertainty in parameters used in
the filter’s process and measurement models by updating the state and
Kalman Filtering covariance using an estimated parameter covariance [11,13]. This
approach can yield computational and processing savings if the
number of parameters is large. Derivation and further discussion of
Stephen Alexander Chee∗ the CKF can be found in [11], ([14] pp. 281–286), and ([15] pp. 387–
McGill University, Montreal, Quebec H3A 2K6, Canada 438). There has been some recent interest in consider analysis.
and Consider analysis has been applied to the problem of planetary entry
James Richard Forbes† [16] and orbit determination [12]. A UKF using the consider frame-
University of Michigan, Ann Arbor, Michigan 48109-2140 work is derived in [17], consider square-root filters and smoothers are
developed in [18], and a UDU formulation of the consider filter is
DOI: 10.2514/1.G000344 presented in [19].
The contribution of this work is the presentation of a consider filter
Downloaded by BEIHANG UNIVERSITY on April 20, 2020 | http://arc.aiaa.org | DOI: 10.2514/1.G000344

applicable to both discrete and hybrid systems subject to a norm-


constrained state estimate. This is accomplished by adjusting the
Kalman gain to solve the minimum variance estimation problem,
I. Introduction while taking into account the constraint on the state estimate, as was

I N MANYengineering applications, knowledge of a system’s state


is needed. Because states are rarely measured directly, the states
are usually estimated using noise corrupted measurements. To
done in [20]. Section II reviews the unconstrained discrete and hybrid
forms of the minimum variance CKF. Section III outlines the discrete
and hybrid norm-constrained CKF (NCCKF). Finally, in Sec. IV, the
improve upon the accuracy of the estimate, information from the NCCKF is applied to a nonlinear attitude estimation problem through
measurements can be combined with knowledge of the system’s the EKF framework, and its performance is compared with the norm-
assumed dynamics. This is the essence of state estimation. constrained Kalman filter developed in [20] through a numerical
In real-time applications, sequential state estimation methods are simulation example.
often employed. Sequential estimators operate by using the most
recent measurements and state estimate. For linear systems, a popular
method that yields an optimal solution is the Kalman filter [1]. Two II. Preliminaries
nonlinear variants of the Kalman filter are the extended Kalman filter The linear discrete-time dynamic system to which the CKF is
(EKF) ([2] pp. 400–409) and the unscented Kalman filter (UKF) [3]. applied is given by [11]
State estimation in the presence of state constraints must be
handled with care. Two popular approaches for addressing state con- xk  Fx;k−1 xk−1  Fp;k−1 p  Gk−1 wk−1 ; wk−1 ∼ N 0; Qk−1 
straints within the Kalman filter framework are the pseudomeasure-
ment method and the projection method. The pseudomeasurement
method, as discussed in [4–6], augments the Kalman filter by where xk ∈ Rn is the state at time tk , p is a set of uncertain parameters
considering the constraint as a perfect measurement without noise. on which the system depends, and wk−1 is the zero-mean Gaussian
The drawback to this method is that it causes the measurement noise process noise with covariance Qk−1  QTk−1 ≥ 0. The corresponding
covariance to be singular, which in turn can lead to numerical continuous-time dynamic system is given by
problems when implemented [7]. The projection method presented in
[8] projects the unconstrained solution to the Kalman filter onto a xt
_  Fx txt Fp tp  Gtwt; wt ∼ N 0;Qtδt − τ
constraint surface for linear equality constraints. This work was
extended in [9] to accommodate nonlinear equality constraints. For discrete-time measurements at time tk , the measurement model is
In [10], the projection method is applied to the UKF. Further given by
information concerning these methods and other algorithms for
handling linear and nonlinear constraints applied to the discrete-time y k  Hx;k xk  Hp;k p  Mk vk ; vk ∼ N 0; Rk 
Kalman filter can be found in [7].
Estimating the state can be further complicated if additional
where y k is the measurement vector at time tk , Mk has full row rank,
parameters, such as measurement biases, are poorly known and left
and vk is the measurement noise with covariance Rk  RTk > 0.
unaccounted for [11,12]. This issue can be addressed by either
augmenting the filter’s state vector to estimate parameters directly or The derivation of the minimum variance CKF for both the discrete-
time and hybrid systems is presented in [11]. The minimum variance
accounting for the uncertainty by using the approach taken in the
CKF is obtained by including the consider states along with the
Schmidt–Kalman filter. The Schmidt–Kalman filter or consider
original states in the state vector and partitioning the gain and the co-
variance matrices with respect to the original states and the consider
Received 23 October 2013; revision received 26 January 2014; accepted for states. By constraining the gain partition multiplying the consider
publication 6 February 2014; published online 8 May 2014. Copyright © state to zero, the minimum variance gain for the original states is
2014 by Stephen Alexander Chee and James Richard Forbes. Published by the
found and the update equations for the consider states are discarded.
American Institute of Aeronautics and Astronautics, Inc., with permission.
Copies of this paper may be made for personal or internal use, on condition These filters are summarized in [11].
that the copier pay the $10.00 per-copy fee to the Copyright Clearance Center,
Inc., 222 Rosewood Drive, Danvers, MA 01923; include the code 1533-3884/
14 and $10.00 in correspondence with the CCC. III. Norm-Constrained Consider Kalman Filter
*Ph.D. Candidate, Department of Mechanical Engineering, 817 Sherbrook A. Fully Constrained State
Street West, Macdonald Engineering Building, Room 459; stephen.chee@
mail.mcgill.ca. Consider the same systems in Sec. II. It is desired p that the

Assistant Professor, Department of Aerospace Engineering, FXB posterior estimate x^ k satisfy the constraint kx^ k k  l. This can be
Building, 1320 Beal Avenue; forbesrj@umich.edu. expressed as
2048
J. GUIDANCE, VOL. 37, NO. 6: ENGINEERING NOTES 2049

x^ Tk x^ k  l (1) continuous-time values at tk . For example, the prior estimate for the
state covariance is P−xx;k  Pxx tk .
To enforce this constraint in the correction step of the CKF, the
objective function for the minimum variance estimator Jk  trfPxx;k g B. Partially Constrained State
is augmented with the constraint using a Lagrange multiplier: Suppose now that only part of the state estimate is constrained.
Let x^ k   q^ Tk z^ Tk T where q^ k satisfies a norm constraint and z^ k is
J^k  trPxx;k   λk x^ Tk x^ k − l unconstrained. The Kalman gain and covariance matrices can be
partitioned as
Following [11], the updated covariance is given by    
Kq;k Pzz;k Pqz;k
Kk  ; Pxx;k   P1;k P2;k   ;
Kz;k Pzq;k Pqq;k
Pxx;k  P−xx;k − Kk Hx;k P−xx;k  Hp;k P−px;k   
Pqp;k
− P−xx;k HTx;k  Pxp;k HTp;k KTk  Kk Wk KTk (2) Pzp;k 
Pzp;k
where W k  Hx;k P−xx;k HTx;k  Hx;k P−xp;k HTp;k  Hp;k P−px;k HTx;k  Substituting these partitioned matrices into the updated covariance
Hp;k Ppp;k HTp;k  Mk Rk MTk . This equation has a similar form to the matrix yields
update covariance for the regular Kalman filter
" # " #
P−qq;k P−qz;k Kq;k
Downloaded by BEIHANG UNIVERSITY on April 20, 2020 | http://arc.aiaa.org | DOI: 10.2514/1.G000344

Pk  P−k − Kk Hk P−k − P−k HTk Kk  Kk V k KTk Pxx;k  − Hx;k  P−1;k P−2;k 


P−zq;k P−zz;k Kz;k
where V k  Hk P−k HTk  Mk Rk MTk . Thus, the derivation of the  Hp;k  P−T
qp;k P−T
zp;k 
norm-constrained CKF can follow the same methodology as the " −T # " − # !
P1;k Pqp;k
derivation for the discrete-time norm-constrained Kalman filter − Hx;k 
T Hp;k  KTq;k
T KTz;k 
presented in [20] by substituting Pxx;k for Pk, Hx;k P−xx;k  Hp;k P−px;k  P−T
2;k P −
zp;k
for Hk P−k , P−xx;k HTx;k  Pxp;k HTp;k  for P−k HTk , and W k for V k. " #
Kq;k
The discrete-time and hybrid minimum variance norm-constrained  W k  KTq;k KTz;k 
CKFs are outlined in Table 1. In these equations, the prior estimate is Kz;k
denoted by a superscript ·− and the quantities p^ k and pt^ denote the
values of p that are assumed by the discrete-time and the hybrid Recognizing that Pqz  PTzq , the partitions of the updated covariance
filters. Because the CKF does not estimate these parameters, p^ k  are given by
p^ k−1 and p_^  0.
Both the discrete-time and the hybrid filters differ only in how the Pqq;k  P−qq;k − Kq;k Hx;k P−1;k  Kq;k Hp;k P−T −T T
qp;k − P1;k Hx;k Kq;k
T

state dynamics are propagated. However, the structure of their


gain and update steps displayed in Table 1 uses notation consistent  P−qp;k HTp;k KTq;k  Kq;k Wk KTq;k ;
with the discrete-time filter. When applying these equations to the Pqz;k  P−qz;k − Kq;k Hx;k P−2;k  Kq;k Hp;k P−T −T T
zp;k − P1;k Hx;k Kz;k
T
hybrid case, the prior estimates are taken to be the propagated
 P−qp;k HTp;k KTz;k − Kq;k W k KTz;k ;

Table 1 Minimum variance norm-constrained consider Kalman Pzz;k  P−zz;k − Kz;k Hx;k P−2;k  Kz;k Hp;k P−T −T T
zp;k − P2;k Hx;k Kq;k
T

filter
 P−zp;k HTp;k KTz;k  Kz;k Wk KTz;k
CKF step Equations
Discrete x^ −k  Fx;k−1 x^ k−1  Fp;k−1 p^ k−1
propagation p^ k  p^ k−1
Notice that Pqq;k and Pzz;k are only dependent on their respective
P−xx;k  Fx;k−1 Pxx;k−1 FTx;k−1  Fx;k−1 Pxp;k−1 FTp;k−1 partitions of the Kalman gain matrix, Kq;k and Kz;k . Given that the
Fp;k−1 Ppx;k−1 FTx;k−1  Fp;k−1 Ppp;k−1 FTp;k−1 objective function of the minimum covariance filter takes the trace of
Gk−1 Qk−1 GTk−1 Pxx;k , then

Pxp;k  Fx;k−1 Pxp;k−1  Fp;k−1 Ppp;k−1
P−px;k  Ppx;k−1 FTx;k−1  Ppp;k−1 Fp;k−1  P−T Jk  trPxx;k   trPqq;k   trPzz;k 
xp;k
Ppp;k  Ppp;k−1
Continuous _^  F txt
xt ^  Fp tpt^ Because Pqq;k is only dependent on Kq;k and Pzz;k is only dependent
on Kz;k , minimizing Jk with respect to Kk allows for each partition of
x
propagation _pt
^ 0
Kk to be calculated independent of one another. Thus, Kq;k is given
P_ xx t  Fx tPxx t  Pxx tFTx t  Pxp tFTp t
Fp tPpx t  GtQtGT t by the gain matrix in Table 1, substituting q^ k for x^ k, and Kz;k can be
P_ xp t  Fx tPxp t  Fp tPpp t found using the traditional formulation.
P_ pp t  0
Gain W k  Hx;k P−xx;k HTx;k  Hx;k P−xp;k HTp;k  Hp;k P−px;k HTx;k
Hp;k P−pp;k HTp;k  Mk Rk MTk IV. Application to Spacecraft Attitude Estimation
Kk  P−xx;k HTx;k  P−xp;k Hp;k W −1
~
k One application to which the norm-constrained CKF can be
rk  y k − Hx;k x^ −k − Hp;k p^ k applied is the spacecraft attitude estimation problem using a unit-
r~k  rTk W−1 k rk length quaternion. It is often the case that the spacecraft is endowed
x~ k  x^ −k  K ~ k rk with a rate gyro that measures the spacecraft’s angular velocity in the
p −1
~ k   l − 1x~ k rk Wk
T
Kk  K jjx~ k jj r~k
spacecraft’s body frame. Unfortunately, gyro measurements are
Update x^ k  x^ −k  Kk rk usually corrupted by both noise and a bias. Often this bias is directly
Pxx;k  P−xx;k − Kk Hx;k P−xx;k  Hp;k P−px;k  estimated. However, modeling the bias is only useful insofar as it
−P−xx;k HTx;k  P−xp;k HTp;k KTk  Kk Wk KTk helps estimate the attitude. Thus, for this investigation, the quaternion
Pxp;k  1 − Kk Hx;k P−xp;k − Kk Hp;k Ppp;k q will be the state vector and the bias β will be considered as a
parameter in the consider framework presented.
2050 J. GUIDANCE, VOL. 37, NO. 6: ENGINEERING NOTES

2 3 2 3 2 13
A. Process Model y m;1
b;k Cbi qk y 1i;k vk
For a principal angle of ϕ about an axis a, the quaternion 6 . 7 6 . 7 6 .. 7
y k  4 .. 5  4 .
. 54 . 5
representation is given by
y m;n
b;k C bi q k y n
i;k vnk
2  3 2 3
a sin ϕ2   Yy 1i;k ; qk 
q4   5 ϵ 6 .. 7
η 4 5qk  vk  hqk ; vk 
cos ϕ2 .
Yy i;k ; qk 
n

where kak  1 and jjqjj  1. By using a power series approach ([21] where n is the number of sensors, y m;j
b;k is the jth vector measurement
pp. 457–460), the following discrete-time approximation of the in the body frame, Cbi qk  is the rotation matrix from the inertial
quaternion kinematics can be made: frame to the body frame corresponding to qk , y ji;k is the corresponding
     reference vector expressed in the inertial frame, vjk is the zero-mean
kωk−1 kΔt Ωωk−1  kωk−1 kΔt white noise with covariance Rjk  RjT
qk ≈ 1 cos  sin qk−1 k > 0, and [22]
2 kωk−1 k 2
 j×  
 fk−1 qk−1 ; ωk−1  (3) y i;k y ji;k ϵk
Yy ji;k ; qk    ηk 1 − ϵ×k −ϵk 
−y jTi;k 0 ηk
where Δt is the time elapsed from tk−1 and tk , ωk−1 is the angular
Downloaded by BEIHANG UNIVERSITY on April 20, 2020 | http://arc.aiaa.org | DOI: 10.2514/1.G000344

velocity at tk−1 , As with the propagation step, the measurement update also needs to
be modified to work with this nonlinear system. Using the EKF
  framework, the innovation is computed using the nonlinear measure-
−ω×k−1 ωk−1 ment equation, and the Kalman gain and the covariance update are
Ωωk−1  
−ωTk−1 0 calculated using Jacobians linearized about the estimated state. The
correction of the estimated state and covariance can be found by
and the superscript ·× denotes the a cross-product matrix as defined substituting q^ k for x^ k, β^ k for p^ k, and hq^ k ; 0 for Hx;k x^ −k  Hp;k p^ k in
in ([21] p. 611). Equation (3) is in fact exact if the angular velocity is Table 1. The measurement Jacobians are given by
constant over Δt. 2 3
As previously mentioned, the gyro measurement of the spacecraft  1 ; q^ − 
Yy
i;k k
angular velocity uk is corrupted by noise wω;k and a static bias β: ∂hqk ; vk  6 7
6 .. 7
Hq;k  6 . 7;
∂q k q^ −k ;0 4 5
uk  ωk  wω;k  β  n ; q^ − 
Yy i;k k

∂hqk ; vk  ∂hqk ; vk 
An estimate of the angular velocity is given by Hβ;k   0; Mk  1
∂β q^ −k ;0 ∂vk q^ − ;0
k

ω
^ k  uk − w
^ ω;k − β^ k (4) where

where w ^ ω;k  0. It should be noted that in the CKF, β^ k  β^ k−1 .  j ; qk   Yy j ; qk 


Yy i;k i;k
The norm-constrained CKF presented in this paper is for linear  
×
systems. To apply it to the nonlinear attitude estimation problem,  y j× j jT j× j
i;k ϵk  y i;k ηk   y i;k ϵk 1 y i;k ϵk  y i;k ηk 
the filter can be modified using the EKF framework. This is
accomplished by propagating the estimate using the nonlinear equa-
tions, assuming no noise and calculating the covariances using
C. Numerical Simulation Results
linearized Jacobians about the filter’s estimate.
The propagation of the estimated state and covariance in discrete To evaluate the performance of the norm-constrained consider
filter, the filter is used to estimate the attitude of a rigid-body
time can be found by substituting q^ k for x^ k, β^ k for p^ k, and spacecraft in a circular orbit. The orbit inclination and altitude are
^ k−1  for Fx;k−1 x^ k−1  Fp;k−1 p^ k−1  in Table 1 where
fk−1 q^ k−1 ; ω 97.6 deg and 600 km, respectively. The spacecraft’s inertia matrix
ω^ k−1 is given in Eq. (4). The discrete-time Jacobians for the discrete- is I  diagf17; 25; 27g kg · m2 , its initial attitude is q0 
time covariance propagation equations are  0 0 0 1 T , and it is tumbling with an initial angular velocity
of ω0   0.001 0.001 0.002 T rad∕s.
   
kω ^ k−1 kΔt Ωω ^ k−1  kω
^ k−1 kΔt The spacecraft is outfitted with a rate gyro and a magnetometer.
Fq;k−1 ≈ 1 cos  sin ; Earth’s magnetic field is modeled as a magnetic dipole. All measure-
2 kω ^ k−1 k 2
  ments are corrupted by zero-mean Gaussian white noise. The
Ωω ^ k−1 Ξq^ k−1  kω^ k−1 kΔt covariance of the gyroscope measurement noise is Qk  σ 2ω 1 with
Fβ;k−1 ≈ cos
kω^ k−1 k2 2 σ ω  3.1623 × 10−7 rad∕s and the standard deviation of the
  magnetometer noise is given by Rk  σ 2m 1 with σ m  150 nT. Gyro
Ξq^ k−1  kω^ k−1 kΔt Ωω ^ k−1 Ξq^ k−1 
− sin − ; measurements are taken every 0.1 s, and magnetometer measure-

^ k−1 k 2 kω^ k−1 k2
ments are taken once every 2 s.
Gk−1  Fβ;k−1 The performance of this norm-constrained consider EKF
(NCCEKF-q) is compared with the norm-constrained EKF
developed in [20] in the presence of a relatively small bias and a
where Ξq^ k    ^ηk 1  ϵ^ ×k T −^ϵk T . relatively large bias. In the first case, the bias is β  0.04 deg ∕h, and
in the second case, β  0.5 deg ∕h. The EKF from [20] is imple-
B. Measurement Model mented by both directly estimating the bias (NCEKF-qb) and
The exteroceptive measurements, measurements of external fea- ignoring the bias (NCEKF-q).
tures relative to the spacecraft, are assumed to be taken by sensors that Because β^ k is treated differently in the NCEKF-qb and the
each provide a vector. The measurement vector has the form NCCEKF-q, the role of its covariance Pββ;k differs as well. When
J. GUIDANCE, VOL. 37, NO. 6: ENGINEERING NOTES 2051

estimating β, the filter will minimize trfPββ;k g. When considering


β, Pββ;k is used by the filter to account for the uncertainty of β when
estimating qk .
Because the purpose of the simulations is to compare the ability of
these filters to cope with a bias, only a modest 3 deg initial attitude
estimate error about each of the principal body axes is applied to
the filters. At time t0 the bias is assumed to be β^ 0  0 by all the filters.
The initial quaternion covariance and quaternion-bias cross co-
variance are Pqq;0  0.21 and Pqβ;0  0 for both cases. The initial
bias covariances are Pββ;0  0.082 1 deg ∕h2 for case 1 and
Pββ;0  1 deg ∕h2 for case 2.

1. Case 1
Figure 1 shows the attitude error in terms of an angle δϕk for each
of the filters over one orbit, where δϕk is the principal angle obtained
from the error quaternion δqk  qk;true ⊗ q^ −1 k . The quaternion
multiplication operator ⊗ is defined in ([21] p. 614) and
q^ −1
k   −^ ϵTk η^ k T . From Fig. 1, it can be seen that the performance Fig. 2 Attitude error for case 2.
Downloaded by BEIHANG UNIVERSITY on April 20, 2020 | http://arc.aiaa.org | DOI: 10.2514/1.G000344

of the NCEKF-qb and NCCEKF-q are relatively close, whereas the


NCEKF-q starts to diverge. the process noise to have a lesser effect on the bias estimate and the
Although the attitude error plots and bias plots are omitted for NCEKF-qb can make a more dramatic improvement in the bias
brevity, it was found that both the NCEKF-qb and the NCCEKF-q are estimate. Nevertheless, both the NCEKF-qb and the NCCEKF-q are
consistent with respect to attitude, where consistency implies that the consistent. For brevity, plots of the quaternion error are omitted.
state estimate remains within the 3σ bounds at all times. The bias
estimates for the NCEKF-qb are also consistent, as is the treatment
3. Remarks on Results
of the bias as a parameter in the NCCEKF-q. The relatively close
performance of the NCEKF-qb and the NCCEKF-q can be attributed These two cases develop a profile of the usefulness of the
to the initial bias having small enough values that the process noise NCCEKF-q versus the NCEKF-qb. For the first case, it is seen that,
causes the NCEKF-qb to make only a modest improvement on the if the uncertainty in the unknown parameters are small, the per-
bias estimate. However, the NCEKF-q becomes inconsistent because formance of the NCCEKF-q is close to the NCEKF-qb. Thus, one
may consider the parameters rather than estimate them, because the
it does not consider the bias.
smaller state results in less computational load. From case 2, it is seen
For the case considered, there are four states of interest associated
that the NCCEKF-q does not perform as well as the NCEKF-qb for
with the quaternion and three considered parameters associated
larger uncertainties in the unknown parameters. As such, if a better
with the bias. By considering the number of operations required for
state estimate is needed and the extra computational load associated
the calculations in the prediction and correction steps as outlined in
with estimating parameters is of no concern, one should estimate the
([23], pp. 661–664), it was found that the NCCEKF-q performs parameters with larger uncertainties. That said, the NCCEKF-q is still
approximately 1798 less floating point operations compared with able to cope with the larger uncertainties and remain consistent while
the NCEKF-qb for the correction step, and 1069 less operations for considering the uncertain parameters, rather than directly estimating
the propagation step. For a contemporary desktop computer, this them. Finally, neglecting the bias altogether leads to inconsistent state
difference may be imperceptible. The savings would likely be more estimates.
significant in the case where the hardware was more restrictive or
if there were a larger number of considered parameters compared
with the number of variables of interest. V. Conclusions
In this study, a consider Kalman filter that directly accounts for a
2. Case 2 norm-constrained state estimate has been derived for discrete-time
Figure 2 shows the attitude error for each of the filters over one and hybrid systems. This is done by solving the minimum variance
orbit. From Fig. 2 it is apparent that the NCCEKF-q no longer optimization problem while accommodating for the norm constraint
performs as well as the NCEKF-qb. In this case, the larger bias causes using a Lagrangian multiplier. The norm-constrained consider
Kalman filter was then applied to a nonlinear spacecraft attitude
estimation problem by employing the EKF framework. Numerical
simulation results were presented showing that, depending on the
size of the gyro bias, the bias can be considered rather than estimated
directly, yielding consistent results with comparable performance to a
filter that directly estimates the bias.

Acknowledgments
The authors thank the anonymous reviewers and the associate
editor for their comments and suggestions that helped improve
the paper.

References
[1] Kalman, R. E., “New Approach to Linear Filtering and Prediction
Problems,” Journal of Basic Engineering, Vol. 82, No. 1, 1960, pp. 35–45.
doi:10.1115/1.3662552
[2] Simon, D., Optimal State Estimation: Kalman, H Infinity, and
Nonlinear Approaches, Wiley, Hoboken, NJ, 2006, pp. 400–412.
[3] Julier, S. J., Uhlmann, J. K., and Durrant-Whyte, H. F., “New Method for
Fig. 1 Attitude error for case 1. the Nonlinear Transformation of Means and Covariance in Filters and
2052 J. GUIDANCE, VOL. 37, NO. 6: ENGINEERING NOTES

Estimators,” IEEE Transactions on Automatic Control, Vol. 45, No. 3, [13] Schmidt, S. F., “Application of State-Space Methods to Navigation
March 2000, pp. 477–482. Problems,” Advances in Control Systems, edited by Leondes, C. T.,
doi:10.1109/9.847726 Vol. 3, Academic Press, New York, 1966, pp. 293–340.
[4] Alouani, A. T., and Blair, W. D., “Use of a Kinematic Constraint in [14] Jazwinski, A. H., Stochastic Processes and Filtering Theory,
Tracking Constant Speed, Maneuvering Targets,” IEEE Transactions on Mathematics in Science and Engineering, Academic Press, New York,
Automatic Control, Vol. 38, No. 7, July 1993, pp. 1107–1111. 1970, pp. 281–286.
doi:10.1109/9.231465 [15] Tapley, B. D., Schutz, B. E., and Born, G. H., Statistical Orbit
[5] Richards, P. W., “Constrained Kalman Filtering Using Pseudo- Determination, Elsevier, New York, 2004, pp. 387–438.
Measurements,” Proceedings of the IEE Colloquium on Algorithms for [16] Zanetti, R., and Bishop, R. H., “Precision Entry Navigation Dead-
Target Tracking, IEEE Publ., Piscataway, NJ, May 1995, pp. 75–79. Reckoning Error Analysis: Theoretical Foundations of the Discrete-
doi:10.1049/ic:19950676 Time Case,” Proceedings of the AAS/AIAA Astrodynamics Specialist
[6] Gupta, N., “Kalman Filtering in the Presence of State Space Equality Conference, Vol. 129, Univelt Inc., San Diego, CA, Aug. 2007,
Constraints,” Proceedings of the 26th Chinese Control Conference, pp. 979–994.
IEEE Publ., Piscataway, NJ, July 2007, pp. 107–113. [17] Lisano, M. E., “Nonlinear Consider Covariance Analysis Using a
doi:10.1109/CHICC.2006.4347158 Sigma-Point Filter Formulation,” Annual AAS Guidance and Control
[7] Simon, D., “Kalman Filtering with State Constraints: A Survey Conference, Univelt Inc., San Diego, CA, Feb. 2006, pp. 129–144.
of Linear and Nonlinear Algorithms,” IET Control Theory and [18] Hinks, J. C., and Psiaki, M. L., “Generalized Square-Root Information
Applications, Vol. 4, No. 8, 2010, pp. 1303–1318. Consider Covariance Analysis for Filters and Smoothers,” Journal of
doi:10.1049/iet-cta.2009.0032 Guidance, Control, and Dynamics, Vol. 36, No. 4, 2013, pp. 1105–1118.
[8] Simon, D., and Chia, T. L., “Kalman Filtering with State Equality doi:10.2514/1.57891
Constraints,” IEEE Transactions on Aerospace and Electronic Systems, [19] Zanetti, R., and D’Souza, C., “Recursive Implementations of the
Vol. 38, No. 1, Jan. 2002, pp. 128–136. Consider Filter,” Proceedings of the Jer-Nan Juang Astrodynamics
Downloaded by BEIHANG UNIVERSITY on April 20, 2020 | http://arc.aiaa.org | DOI: 10.2514/1.G000344

doi:10.1109/7.993234 Symposium, Univelt Inc., San Diego, CA, June 2012, pp. 297–313.
[9] Yang, C., and Blasch, E., “Kalman Filtering with Nonlinear State [20] Zanetti, R., Majji, M., Bishop, R. H., and Mortari, D., “Norm-
Constraints,” IEEE Transactions on Aerospace and Electronic Systems, Constrained Kalman Filtering,” Journal of Guidance, Control, and
Vol. 45, No. 1, Jan. 2009, pp. 70–84. Dynamics, Vol. 32, No. 5, 2009, pp. 1458–1465.
doi:10.1109/TAES.2009.4805264 doi:10.2514/1.43119
[10] Julier, S. J., and LaViola, J. J., “On Kalman Filtering with Nonlinear [21] Crassidis, J. L., and Junkins, J. L., Optimal Estimation of Dynamic
Equality Constraints,” IEEE Transactions on Signal Processing, Systems, Chapman & Hall/CRC Applied Mathematics and Nonlinear
Vol. 55, No. 6, June 2007, pp. 2774–2784. Science Series, 2nd ed., CRC Press, Boca Raton, FL, 2012, pp. 457–
doi:10.1109/TSP.2007.893949 460, 611–612, 614.
[11] Woodbury, D. P., and Junkins, J. L., “On the Consider Kalman Filter,” [22] Leung, W. S., and Damaren, C. J., “Comparison of the Pseudo-Linear
AIAA Guidance, Navigation, and Control Conference, AIAA Paper and Extended Kalman Filter for Spacecraft Attitude Estimation,” AIAA
2010-7752, Aug. 2010. Guidance, Navigation, and Control Conference, AIAA Paper 2004-
doi:10.2514/6.2010-7752 5341, Aug. 2004.
[12] Hough, M. E., “Orbit Determination with Improved Covariance doi:10.2514/6.2004-5341
Fidelity, Including Sensor Measurement Biases,” Journal of Guidance, [23] Boyd, S., and Vandenberghe, L., Convex Optimization, Cambridge
Control, and Dynamics, Vol. 34, No. 3, 2011, pp. 903–911. Univ. Press, New York, 2004, pp. 661–664.
doi:10.2514/1.53053
This article has been cited by:

1. Hannes Sommer, James Richard Forbes, Roland Siegwart, Paul Furgale. 2016. Continuous-Time Estimation of Attitude
Using B-Splines on Lie Groups. Journal of Guidance, Control, and Dynamics 39:2, 242-261. [Abstract] [Full Text] [PDF]
[PDF Plus]
Downloaded by BEIHANG UNIVERSITY on April 20, 2020 | http://arc.aiaa.org | DOI: 10.2514/1.G000344

You might also like