Hostname: page-component-745bb68f8f-v2bm5 Total loading time: 0 Render date: 2025-02-11T08:32:51.189Z Has data issue: false hasContentIssue false

Novel Hybrid of LS-SVM and Kalman Filter for GPS/INS Integration

Published online by Cambridge University Press:  23 February 2010

Zhenkai Xu*
Affiliation:
(Southeast University, Nanjing, China) (University of New South Wales, Sydney, Australia)
Yong Li
Affiliation:
(University of New South Wales, Sydney, Australia)
Chris Rizos
Affiliation:
(University of New South Wales, Sydney, Australia)
Xiaosu Xu
Affiliation:
(Southeast University, Nanjing, China)
Rights & Permissions [Opens in a new window]

Abstract

Integration of Global Positioning System (GPS) and Inertial Navigation System (INS) technologies can overcome the drawbacks of the individual systems. One of the advantages is that the integrated solution can provide continuous navigation capability even during GPS outages. However, bridging the GPS outages is still a challenge when Micro-Electro-Mechanical System (MEMS) inertial sensors are used. Methods being currently explored by the research community include applying vehicle motion constraints, optimal smoother, and artificial intelligence (AI) techniques. In the research area of AI, the neural network (NN) approach has been extensively utilised up to the present. In an NN-based integrated system, a Kalman filter (KF) estimates position, velocity and attitude errors, as well as the inertial sensor errors, to output navigation solutions while GPS signals are available. At the same time, an NN is trained to map the vehicle dynamics with corresponding KF states, and to correct INS measurements when GPS measurements are unavailable. To achieve good performance it is critical to select suitable quality and an optimal number of samples for the NN. This is sometimes too rigorous a requirement which limits real world application of NN-based methods.

The support vector machine (SVM) approach is based on the structural risk minimisation principle, instead of the minimised empirical error principle that is commonly implemented in an NN. The SVM can avoid local minimisation and over-fitting problems in an NN, and therefore potentially can achieve a higher level of global performance. This paper focuses on the least squares support vector machine (LS-SVM), which can solve highly nonlinear and noisy black-box modelling problems. This paper explores the application of the LS-SVM to aid the GPS/INS integrated system, especially during GPS outages. The paper describes the principles of the LS-SVM and of the KF hybrid method, and introduces the LS-SVM regression algorithm. Field test data is processed to evaluate the performance of the proposed approach.

Type
Research Article
Copyright
Copyright © The Royal Institute of Navigation 2010

1. INTRODUCTION

An integrated GPS/INS system can provide precise navigation solutions while GPS signals are available. The GPS solution has a consistent and long-term stable accuracy, which is used to update the INS solution. Meanwhile, the accurate short-term INS solution can be used to bridge GPS outages. The KF is typically used to fuse the measurements from the GPS and INS devices. Due to the increasing use of low-cost MEMS inertial sensors for land vehicle applications, however, the traditional KF methodology is found to be inadequate due to the poor quality of the MEMS inertial measurements. When GPS outages occur, for example in tunnels, urban canyons, or indoors, the accuracy of the navigation system will degrade sharply, as the KF cannot be updated with the GPS measurements. It is a challenge to develop an optimal real-time GPS/INS integration algorithm that can maintain required system performance during GPS outages [Reference Li, Mumford and Rizos1Reference Goodall, El-Sheimy and Chiang4].

Combination of the KF and neural network (NN) technique is one of the widely-used methods to improve the performance of GPS/INS integrated systems, as in, for example, the NN-aided adaptive extended KF (EKF) [Reference Jwo and Huang5], the NN-tuning KF [Reference Korniyenko, Sharawi and Aloi6], the use of the NN for de-noising MEMS-based inertial data [Reference El-Rabbany and El-Diasty7], and the NN/KF hybrid approach [Reference Wang, Wang, Sinclair and Watts8]. In an NN-based integrated system, an NN is trained to map the vehicle dynamics with corresponding KF states during periods of good quality GPS data. Once the NN is trained, its output is then used to correct the INS when the GPS solution becomes unavailable.

However, it is critical to select sufficient data samples of good quality for the NN to deliver good performance. This is sometimes too rigorous a requirement which limits real world application of the NN-based methods. Furthermore, an NN-based method has some drawbacks, such as the existence of many local minimum solutions and the difficulty in choosing the number of hidden units. This paper explores the application of a new class of kernel-based techniques known as LS-SVM to aid GPS/INS integration. In contrast to the NN approaches, the SVM, which can be characterised by the convex optimisation problems, has been developed in the area of statistical learning theory and structural risk minimisation [Reference Vapnik9][Reference Vapnik10]. LS-SVM models scale very well to high dimension input spaces. Moreover, using weighted least squares and special pruning techniques, it can be employed for robust nonlinear estimation. This paper describes the LS-SVM regression algorithm and the implementation of an LS-SVM/KF hybrid method for GPS/INS integration. As with the NN approach, the LS-SVM is used to correct the INS errors during GPS outages, based on the modelling achieved from the advance training when GPS is available. Field test data is used to evaluate the performance of the proposed method and the result are compared with the more common NN-aided GPS/INS techniques.

2. INTEGRATION KALMAN FILTER

As the core of an integrated system, the integration KF must be carefully designed. A 15-state KF is used for the experiments reported in this paper, with the states listed in Table 1. The inertial measurement unit (IMU) sensor errors are the various scale factor errors, biases, non-orthogonality errors, and noise terms.

Table 1. States of the integration KF.

The INS error equation in the psi-angle form is [Reference Bar-Itzhack and Berman11]:

(1)
\delta \mathop r\limits^{ \bullet } \equals \minus \omega _{en} \times \delta r \plus \delta v\
(2)
\delta \mathop v\limits^{ \bullet } \equals \minus \lpar \omega _{ie} \plus \omega _{in} \rpar \times \delta v\ \plus \ f\ \times \delta \psi \plus \varepsilon _{a}
(3)
\delta \mathop \psi \limits^{ \bullet } \equals \minus \omega _{in} \times \delta \psi \plus \varepsilon _{g}

The sensor errors are modelled as random walk processes:

(4)
\mathop {\varepsilon _{a} }\limits^{ \bullet } \equals w_{a}
(5)
\mathop {\varepsilon _{g} }\limits^{ \bullet } \equals w_{g}

where δr, δν and δψ are the error vectors of position, velocity and angle, respectively. εa and εg are the errors of the accelerometers and gyroscopes, respectively. w a and w g are the white noises associated with the accelerometers and gyroscopes, respectively. ωie is the Earth rate vector; ωin is the angular rate vector of the navigation frame relative to the inertial frame; ωenin=−ωie; and f is the specific force.

The process model of the system in Equations (1) – (5) can be also written in matrix form:

(6)
\left[{\matrix{ {\delta \mathop r\limits^{ \bullet } } \hfill \cr {\delta \mathop v\limits^{ \bullet } } \hfill \cr {\delta \mathop \psi \limits^{ \bullet } } \hfill \cr {\mathop {\varepsilon _{a} }\limits^{ \bullet } } \hfill \cr {\mathop {\varepsilon _{g} }\limits^{ \bullet } } \hfill \cr} } \right]\ \equals \left[ {\matrix{ { \minus \omega _{en}^{ \times } } \hfill \tab \hfill I \hfill \tab \hfill 0 \hfill \tab \hfill 0 \hfill \tab \hfill 0 \hfill \cr \hfill 0 \hfill \tab \hfill { \minus \lpar \omega _{ie} \plus \omega _{in} \rpar ^{ \times } } \hfill \tab \hfill {f^{ \times } } \hfill \tab \hfill {C_{nb} } \hfill \tab \hfill 0 \hfill \cr \hfill 0 \hfill \tab \hfill 0 \hfill \tab \hfill { \minus \omega _{in}^{ \times } \ \ } \hfill \tab \hfill 0 \hfill \tab \hfill {C_{nb} } \hfill \cr \hfill 0 \hfill \tab \hfill 0 \hfill \tab \hfill 0 \hfill \tab \hfill 0 \hfill \tab \hfill 0 \hfill \cr \hfill 0 \hfill \tab \hfill 0 \hfill \tab \hfill 0 \hfill \tab \hfill 0 \hfill \tab \hfill 0 \hfill \cr} } \right]\ \left[ {\matrix{ {\delta r} \hfill \cr {\delta v} \hfill \cr {\delta \psi } \hfill \cr {\varepsilon _{a} } \hfill \cr {\varepsilon _{g} } \hfill \cr} } \right]\ \plus \left[ {\matrix{ {w_{r} } \hfill \cr {w_{v} } \hfill \cr {w_{\psi } } \hfill \cr {w_{a} } \hfill \cr {w_{g} } \hfill \cr} } \right]

where the direction cosine matrix C nb implements the transformation from the body-frame coordinate system to the navigation-frame coordinate system.

The observation vectors of the KF are formed by differencing the GPS and INS positions (rgps, rins) and the velocities (vgps, vins). When GPS data is available, the observation vectors are updated with the GPS and INS measurements. However, when GPS outages occur the KF cannot be updated with the GPS measurements and the accuracy of the navigation system will degrade sharply. In the case of no more measurement correction information, it is a challenge to improve the accuracy of the INS-only navigation solution.

3. LS-SVM

LS-SVM is widely used for nonlinear estimation. The LS-SVM regression algorithm is used here to improve the accuracy of the INS-only navigation solution during GPS outages.

3.1. LS-SVM Regression Algorithm

Given a training set \left\{ {x_{k} \comma y_{k} } \right\}_{k \equals \setnum{1}}^{N}, the LS-SVM model for nonlinear function estimation has the following representation in the feature space [Reference Vapnik, Suykens and Vandewalle12]:

(7)
y\lpar x\rpar \ \equals \ \omega ^{T} \varphi \lpar x\rpar \ \plus \ b

where the input data is xn and the corresponding output is y. The nonlinear function ϕ maps the input space to a so-called higher dimensional feature space. The term b is the bias term.

The optimisation problem is:

(8)
\mathop {min}\limits_{\omega \comma b\comma e} \ J\lpar \omega \comma e\rpar \equals {1 \over 2}\omega ^{T} \omega \plus \gamma {1 \over 2}\sum\limits_{k \equals \setnum{1}}^{N} {e_{k} ^{\setnum{2}} } \comma

subject to the equality constraints:

(9)
y_{k} \equals \omega ^{T} \varphi \lpar x_{k} \rpar \plus b \plus e_{k} \comma \ k \equals 1\comma \ldots \comma N.

The cost function with squared error and regularisation corresponds to a form of ridge regression [Reference Golub and Van Loan13].

To solve the optimisation problem above, the Lagrangian function is constructed:

(10)
L\lpar \omega \comma b\comma e\comma \alpha \rpar \equals J\lpar \omega \comma e\rpar \minus \sum\limits_{k \equals \setnum{1}}^{N} {\alpha _{k} \lcub \omega ^{T} \varphi \lpar x_{K} \rpar \plus b \plus e_{k} \minus y_{k} \rcub }

where αk are the Lagrange multipliers. The conditions for optimality are given by:

(11)
\left\{ {\matrix{ {{{\partial L} \over {\partial \omega }} \equals 0\comma \ } \hfill \tab \to \hfill \tab {\omega \equals \sum\limits_{k \equals \setnum{1}}^{N} {\alpha _{k} \varphi \lpar x_{k} \rpar } } \hfill \tab {} \hfill \cr {{{\partial L} \over {\partial b}} \equals 0\comma \ } \hfill \tab \to \hfill \tab {\sum\limits_{k \equals \setnum{1}}^{N} {\alpha _{k} \equals 0} } \hfill \tab {} \hfill \cr {{{\partial L} \over {\partial e_{k} }} \equals 0\comma } \hfill \tab \to \hfill \tab {\alpha _{k} \equals \gamma e_{k} \comma } \hfill \tab {k \equals 1\comma \ldots \comma N} \hfill \cr {{{\partial L} \over {\partial \alpha _{k} }} \equals 0.} \hfill \tab \to \hfill \tab {\omega ^{T} \varphi \lpar x_{K} \rpar \plus b \plus e_{k} \minus y_{k} \equals 0\comma } \hfill \tab {k \equals 1\comma \ldots \comma N} \hfill \cr} } \right.

The solution of Equation (11), αk and b, can be computed from the input of the sample sets when the LS-SVM is trained. Applying the Mercer condition one obtains:

(12)
K\lpar x_{k} \comma x_{l} \rpar \equals \varphi \lpar x_{k} \rpar ^{T} \varphi \lpar x_{l} \rpar \comma \quad k\comma l \equals 1\comma \ldots \comma N

As a result, the LS-SVM model for nonlinear function estimation becomes:

(13)
y\lpar x\rpar \equals \sum\limits_{k \equals \setnum{1}}^{N} {\alpha _{k} } K\lpar x\comma x_{k} \rpar \plus b

In this paper the most universal RBF kernels are chosen as the kernel function of the LS-SVM:

(14)
K\lpar x\comma x_{k} \rpar \equals \exp \lpar\! \minus \left\Vert {x_{k} \minus x} \right\Vert_{\setnum{2}}^{\setnum{2}} \sol \sigma ^{\setnum{2}} \rpar.

Note that in the case of RBF kernels, only two additional tuning parameters, γ (regularisation parameter) and σ (kernel width), need to be selected. They need to be an optimal combination, determined before the LS-SVM is trained. There are several methods that can be used, e.g. bootstrapping [Reference Vapnik, Suykens and Vandewalle12], VC bounds statistical learning theory [Reference Vapnik9][Reference Vapnik10], genetic algorithms, and inference or Bayesian learning methods [Reference Van Gestel, Suykens, Lanckriet, Lambrechts, De Moor and Vandewalle14]. A simplified cross-validation method is developed in this paper, which defines a training set, consisting of the validation and the verification subsets. In the validation subset, the LS-SVM is trained with some empirical combinations of tuning parameters. Those combinations, which enable the output of the LS-SVM to reach the given accuracy, are selected as the primary tuning parameters. Then they are used to further train the LS-SVM with the verification set, and the final selection of tuning parameters is made. In addition, system modelling is performed along with the process of selection of tuning parameters so that the system model is also obtained. A well-trained LS-SVM can be used in many physical scenarios for different definitions of the input/output.

3.2. The Input/Output Design of LS-SVM

A KF state's variation with time is mainly caused by vehicle dynamics (changes of vehicle velocity and attitude). It has been found that there is a relatively high correlation between vehicle dynamics and some KF states, in particular the velocity and attitude errors and the horizontal accelerometer biases [Reference Wang, Wang, Sinclair and Watts8]. It is difficult to model this correlation, but it could be mapped by a properly designed LS-SVM after adequate training. When the GPS data is unavailable, with the input of vehicle dynamics information the LS-SVM outputs the prediction of the KF states, which are used to compensate the INS solution (as the integration KF does when the GPS data is available).

The dynamic variations are selected as the input of the LS-SVM and the KF states are selected as the output. For land vehicle applications, vertical movement can be ignored and the input of the LS-SVM can be selected as:

(15)
LS \minus SVM_{in} \equals \lsqb \rmDelta v_{N} \comma \rmDelta V_{E} \comma \rmDelta \psi _{H} \rsqb

To reduce the computational load, only the KF states that have a major impact on the accuracy of the navigation solutions will be selected as the output of the LS-SVM. The simulation results show that δν and δψ are the most significant factors. The quality of the solution with just δν and δψ updated is very close to that when all states (except δr) are updated. Therefore the output of the LS-SVM can be simplified as:

(16)
LS \minus SVM_{out} \equals \lsqb \delta v_{N\comma } \delta v_{E} \comma \delta v_{D} \comma \delta \psi _{H} \comma \delta \psi _{P} \comma \delta \psi _{R} \rsqb

The structure of input and output is consistently implemented for the training and prediction stages.

4. LS-SVM AND KF HYBRID METHOD FOR GPS/INS INTEGRATION SYSTEM

With the selected input and output of the LS-SVM for GPS/INS integration, the LS-SVM/KF hybrid architecture can be designed. The hybrid method consists of two stages. The first is the LS-SVM/ KF hybrid system. The second is the LS-SVM-based prediction during GPS outages.

4.1. LS-SVM and KF Hybrid Architecture for GPS/INS Integration System

When GPS data is available the LS-SVM functions in the training mode. The configuration of the LS-SVM/KF hybrid system for GPS/INS integration is illustrated in Figure 1. The vehicle's dynamics are derived from the navigation solution and continuously input to the LS-SVM for training. The KF estimates of δν and δψ are introduced into the LS-SVM as the target vectors of the training. The observation vectors of the KF are formed by differencing the GPS and INS positions (rgps, rins) and the velocities (vgps, vins).

Figure 1. Configuration of the LS-SVM/ KF hybrid system.

4.2. Configuration of the LS-SVM-based prediction during GPS outages

Without updating by GPS the KF estimates remain unchanged from the values at the last epoch before the GPS outage. The integrated system actually becomes simply a stand-alone INS. Figure 2 illustrates the configuration of the LS-SVM-based prediction during a GPS outage. The LS-SVM functions in the prediction mode, in which the output of the LS-SVM is used for error compensation. The vehicle dynamics derived from the navigation solution are continuously input into the LS-SVM, as was done during the training phase.

Figure 2. Configuration of the LS-SVM-based prediction during GPS outages.

5. TEST

A low-cost FPGA-based GPS/INS integration system was utilised to collect field test data in order to evaluate the performance of the proposed method. The hardware components of the system included Boeing's C-MIGITS II IMU, an OmniStar GPS receiver, and an FPGA device built on the Nios II soft-core processor [Reference Li, Mumford and Rizos1][Reference Li, Mumford and Rizos15]. The C-MIGITS II has a gyro bias of about 30 deg/hr and an accelerometer bias of approximately 4 mg [16]. It can output the inertial data (delta velocity and delta theta) for subsequent processing. The trajectory of the test is shown in Figure 3, where four 30-second simulated GPS outages are marked by red lines.

Figure 3. Trajectory of the vehicle in the field test.

5.1. LS-SVM Training

Two independent sets of 100 epoch sample vectors were utilised to train the LS-SVM. The first set was used for the validation, in which the LS-SVM was trained with nine combinations of empirical σ and γ. The parameter e was chosen as 10−2, which is related to the accuracy of the model fitting. The velocity and attitude errors are the output of the LS-SVM. The training results are listed in Table 2, where the tests 4–7 were selected as the primary tuning parameters, which were to be used to further train the LS-SVM with the verification set, and the results are listed in Table 3. From Table 3, σ=50 and γ=1000 were the final selection of tuning parameters. Finally, using both the validation and verification sets as well as the selected tuning parameters, the LS-SVM was trained again to obtain the system model.

Table 2. LS-SVM training results with the validation set.

Table 3. LS-SVM training results with verification set.

5.2. Prediction and Analyses

In order to assess the performance of the hybrid method, four 30-second GPS outages were simulated. The LS-SVM result was compared with the INS–only solution and the NN/KF hybrid solution during these outages. The back propagation (BP) NN/KF hybrid method has the same input/output as the LS-SVM. The number of the training was 5000. The activation function of the hidden layer is sigmoid. The BP NN has three neurons in the input layer and six neurons for the output layer, as well as for the 100 epoch training set. The results during the four outages are listed in Tables 4, 5 and 6, where the position, velocity and attitude errors from the INS-only, LS-SVM and NN methods are compared.

Table 4. The position errors (m) from the INS-only, NN/KF and LS-SVM/KF methods.

Table 5. The velocity errors (m/s) from the INS-only, NN/KF and LS-SVM/KF methods.

Table 6. The attitude errors (deg) from the INS-only, NN/KF and LS-SVM/KF methods.

Note that the errors for the LS-SVM/KF are smaller than the ones for the NN/KF and INS-only methods, confirming that the proposed algorithm can improve system performance. Figure 4 shows the attitude errors derived associated with the #1 GPS outage period. The INS-only solution is depicted in blue, the NN/KF solution in red, and the SVM/KF solution in green.

Figure 4. The attitude errors (deg) for the INS-only, NN/KF and LS-SVM/KF methods.

It is evident from Figure 4 that both the LS-SVM/KF and NN/KF can reduce the attitude errors, and that the LS-SVM/KF solution has the smallest error. Although before epoch 184906 the error of the LS-SVM solution sometimes is slightly larger than that of the NN/KF solution, the LS-SVM/KF always has smaller errors than the NN/KF after that epoch. The improvement is particularly obvious in the last segment of the period. The result shows that the proposed hybrid method is very effective as it decreases the attitude errors by about 40% and the position errors by about 20%.

To more clearly demonstrate how the proposed algorithm improves the accuracy of the solution, a 15-second GPS outage is assumed from 184920 sec to 184934 sec. The errors compensated with the prediction of the LS-SVM are shown in Figures 5, 6 and 7, where the position, velocity and attitude errors derived from the INS-only (in blue) and the LS-SVM/KF (in red) methods are compared. In those figures one can see that when the length of the GPS outage is shortened from 30 s to 15 s, the error of the LS-SVM/KF hybrid is much closer to zero than that of the INS-only, which indicates that the short-period prediction of the LS-SVM/KF has a higher accuracy than the long-period prediction. From these 15-second GPS outage results it can be seen that the proposed hybrid method decreases by about 96% the position errors, 87% the velocity errors and 81% the attitude errors.

Figure 5. The position errors (m) for the INS-only and LS-SVM/KF methods.

Figure 6. The velocity errors (m/s) for the INS-only and LS-SVM/KF methods.

Figure 7. The attitude errors (deg) for the INS-only and LS-SVM/KF methods.

6. CONCLUDING REMARKS

The principles of the LS-SVM and KF hybrid method are described and implemented in an integrated GPS/INS system. The input and output of an LS-SVM are selected on the basis of correlations between the dynamic variations and the KF states. Once the LS-SVM is properly trained in the training phase, its prediction can be used to correct the INS solution during GPS outages. Field test data is used to evaluate the performance of the proposed method. The LS-SVM results show an improved overall performance in comparison with the results of the NN and the INS-only solutions. The short-period prediction of the LS-SVM/KF has a higher accuracy than the long-period prediction. Further research is required in order to determine the relationship between the prediction accuracy and the outage length, to model the error behaviour and its relationship with the number of samples used for training, and to investigate the appropriate selection of parameters for the LS-SVM/KF prediction.

References

REFERENCES

[1]Li, Y., Mumford, P. and Rizos, C. (2008). “A Real-time GPS/INS Integrated System”, Coordinates, Vol. IV, No. 3, 1217, March 2008.Google Scholar
[2]Brown, A., and Lu, Y. (2004). “Performance Test Results on an Integrated GPS/MEMS Inertial Navigation Package”, in Proc. of 17th International Technical Meeting of the Satellite Division, U.S. Institute of Navigation, Long Beach, CA, Sept 2124. 2004, 825832.Google Scholar
[3]Jaffe, R., Bonomi, S., and Madni, A. M.. (2004). “Miniature MEMS Quartz INS/GPS Description and Performance Attributes”, in Proc. of 17th International Technical Meeting of the Satellite Division, U.S. Institute of Navigation, Long Beach, CA, Sept 2124. 2004, 852863.Google Scholar
[4]Goodall, C., El-Sheimy, N., and Chiang, K. W. (2005). “The Development of a GPS/MEMS INS Integrated System Utilising a Hybrid Processing Architecture”, in Proc. of 18th International Technical Meeting of the Satellite Division, U.S. Institute of Navigation, Long Beach, CA, September 1316. 2005, 14441455.Google Scholar
[5]Jwo, D. J., and Huang, H-C. (2004). “Neural Network Aided Adaptive Extended Kalman Filtering Approach for DGPS Positioning”, Journal of Navigation, 57, 449463.CrossRefGoogle Scholar
[6]Korniyenko, O. V., Sharawi, M. S., and Aloi, D. N. (2005). “Neural Network Based Approach for Tuning Kalman Filter”, presented at IEEE Electro/Information Technology Conference (EIT 2005), Lincoln – Nebraska, May 22–25, 2005, 15.Google Scholar
[7]El-Rabbany, A., and El-Diasty, M. (2004). “An Efficient Neural Network Model for De-noising of MEMS-based Inertial Data”, Journal of Navigation, 57, 407415.CrossRefGoogle Scholar
[8]Wang, J. J., Wang, J., Sinclair, D. and Watts, L. (2006). “A Neural Network and Kalman Filter Hybrid Approach for GPS/INS Integration”, 12th IAIN Congress & 2006 International Symposium on GPS/GNSS, Jeju, Korea, October 18–20, 277282.Google Scholar
[9]Vapnik, V. (1995). The Nature of Statistical Learning Theory, Springer-Verlag, New-York.CrossRefGoogle Scholar
[10]Vapnik, V. (1998). Statistical Learning Theory, John Wiley, New-York.Google Scholar
[11]Bar-Itzhack, I. Y., and Berman, N. (1988). “Control Theoretical Approach to Inertial Navigation Systems”, Journal of Guidance, Control and Dynamics, Vol. 11, No. 3, 237245.CrossRefGoogle Scholar
[12]Vapnik, V. (1998). “The Support Vector Method of Function Estimation”, in Nonlinear Modeling: Advanced Black-box Techniques, Suykens, J.A.K., Vandewalle, J. (Eds.), Kluwer Academic Publishers, Boston, 5585.CrossRefGoogle Scholar
[13]Golub, G. H. and Van Loan, C. F. (1989). Matrix Computations, Baltimore MD: Johns Hopkins University Press.Google Scholar
[14]Van Gestel, T., Suykens, J. A. K., Lanckriet, G., Lambrechts, A., De Moor, B. and Vandewalle, J. (2002). “A Bayesian Framework for Least Squares Support Vector Machine Classifiers”, Nerual Computation, May 2002, Vol. 14, No. 5, Pages 11151147.CrossRefGoogle ScholarPubMed
[15]Li, Y., Mumford, P., and Rizos, C. (2008). “Seamless Navigation Through GPS Outages – A Low-cost GPS/INS Solution”, Inside GNSS, July/August 2008, 3945.Google Scholar
[16]Boeing North American Inc, User's Manual of C-MIGITS II., 1997, 67.Google Scholar
Figure 0

Table 1. States of the integration KF.

Figure 1

Figure 1. Configuration of the LS-SVM/ KF hybrid system.

Figure 2

Figure 2. Configuration of the LS-SVM-based prediction during GPS outages.

Figure 3

Figure 3. Trajectory of the vehicle in the field test.

Figure 4

Table 2. LS-SVM training results with the validation set.

Figure 5

Table 3. LS-SVM training results with verification set.

Figure 6

Table 4. The position errors (m) from the INS-only, NN/KF and LS-SVM/KF methods.

Figure 7

Table 5. The velocity errors (m/s) from the INS-only, NN/KF and LS-SVM/KF methods.

Figure 8

Table 6. The attitude errors (deg) from the INS-only, NN/KF and LS-SVM/KF methods.

Figure 9

Figure 4. The attitude errors (deg) for the INS-only, NN/KF and LS-SVM/KF methods.

Figure 10

Figure 5. The position errors (m) for the INS-only and LS-SVM/KF methods.

Figure 11

Figure 6. The velocity errors (m/s) for the INS-only and LS-SVM/KF methods.

Figure 12

Figure 7. The attitude errors (deg) for the INS-only and LS-SVM/KF methods.