Abstract
The Extended Kalman Filter (EKF) is currently a dominant sensor fusion method for mobile devices, robotics, and autonomous vehicles. Its performance heavily depends on the selection of EKF parameters. Therefore, the optimal selection of parameters is a critical factor in EKF design and use. In this paper, a methodical and efficient method of EKF parameter tuning is presented. The tuning framework uses nominal parameters generated by Gauss Markov (GM) and Allan Variance (AV) methods that are tuned by Genetic Algorithms (GA) accelerated by Design of Experiments (DoE). This framework has been implemented in MATLAB and tested using simulations and real data under a tightly coupled EKF that fuses IMU and GNSS measurements of a self-driving car provided by the Blackberry QNX company. The results demonstrate that GA-tuned parameters increase accuracy substantially over nominally tuned parameters, and that the DoE technique consistently improves the convergence behavior of the GA.
- extended Kalman Filter < Multisensor Navigation
- genetic algorithm < Algorithms and Methods
- tightly-coupled data fusion < Land Based Applications
1 INTRODUCTION
1.1 Motivation
Pose estimation is a core functionality to a wide variety of robotic and mobile systems. Millions of people use this functionality on their smartphones and in-car navigation systems every day to know where they are. Autonomous vehicles and UAV rely on accurate localization capabilities to safely and effectively navigate to their mission objectives. The pose estimation scheme explored in this paper uses Global Navigation Satellite Systems (GNSS) and Inertial Navigation Systems (INS) (Paul, 2013; Savage, 2000) fused with an Extended Kalman Filter (EKF) as shown in Figure 1 (Farrell, 2008).
The noise parameters of sensors and measurements in the EKF heavily impact the performance of the filter’s state estimation (Grewal & Andrews, 1993). Such parameters are used to model random walk, scale factors, and bias values of INS and GNSS systems. These parameters allow the filter to determine, at any moment, the comparative confidence of each sensor. There is no closed form solution to determine these parameters, and current methods of finding them mostly rely on manual tuning, which is tedious, slow, and does not provide optimal results.
1.2 Existing techniques
For an inertial system, the current approach of choosing these parameters is to generate long records of static measurements and use stochastic modeling methods such as Gauss-Markov (GM) random processes and Allan Variance (AV) to obtain covariance values (Elder, 2016; Miroslav & Mikuláš, 2016). These methods do not handle disturbances or changes in the environment and may not result in accurate tuning for practical dynamic motions. The application of grid-search methods to tune EKF parameters may be considered, but grid-search methods exhaustively search through manually specified sets of parameters, resulting in them being time and resource consuming and imposing several challenges in real-time applications.
1.3 Objective and methodology
The objective of this research is to demonstrate an efficient framework that can be easily used by engineers and researchers to facilitate the tedious task of EKF parameter optimization. The developed framework is to be used to robustly tune parameters of an EKF that fuses an inertial measurement unit (IMU) with a GNSS in a tightly coupled integration scheme. The approach consists of using statistical methods and Genetic Algorithms (GA) accelerated by Design of Experiment (DoE) techniques to produce the best noise parameters that minimize the error of the position, velocity, and orientation estimation of the system.
GA are heuristic search techniques that are based on the theory of evolution and natural selection. GA have been proven to outperform grid-search methods in terms of computation. In addition, GA techniques avoid local minima problems by keeping diverse sets of solutions. Another benefit of GA is that they can be efficiently implemented on parallel computing platforms (Goldberg, 1989).
The standard GA method starts with a randomly initialized population of parameters. In each GA iteration, genetic operations such as mutations and crossovers are applied on the fit individuals of a population leading to a new generation (offspring) that is ranked according to fitness. Over many generations, the average and best fitness of the population is expected to improve. The GA iterations are terminated when no further significant improvements in fitness are achieved, or if a specified number of generations is reached. The fitness in this work is the root mean square error (RMSE) of the position, velocity, and orientation estimations of a vehicle over a known ground-truth trajectory.
The DoE technique finds the relative impact of each tunable parameter and directs the GA to tune the most impactful parameters first in order to accelerate the tuning, which takes many hours to complete on standard machines (Antony, 2014). In this paper, the described GA steps have been applied to achieve the objective of this work: the optimization of EKF parameters of a full 3D IMU/GNSS tightly coupled system. First, stochastic modeling methods (i.e., GM random processes and AV) are used to obtain an initial set of noise parameters called the “nominal design point.” The DoE technique is then applied on the obtained “nominal design point” to identify the relative impact each parameter has on the EKF performance. These parameter impacts are then used to direct and guide the GA search to reach the most accurate tuning parameters quickly and efficiently. A high-level block diagram of the system is displayed in Figure 2.
2 DESIGN DETAILS
2.1 Tuning parameters
The pertinent EKF system contains both parameters that are approximately measurable and parameters that are completely unknown. The process covariance matrix for instance, commonly denoted Q, contains the random walk error of the IMU sensors, which can be estimated through certain modeling techniques but cannot be calculated optimally. Although the measurement noise covariance matrix, denoted R, is commonly mentioned in sensors datasheets (e.g., GNSS receiver specifications), it may require a scaling factor to be consistent with other filter parameters (initial P and Q). These matrices are of high importance since they directly impact the degree to which the filter favors one sensor reading over another, and small variations in some values may result in a complete divergence in the estimation. Therefore, optimal tuning of these matrices is strongly desired.
GM processes are used to model the bias and scale factor values of the INS and comprise the standard deviation and time constant of both the bias and scale factors (Unsal & Demirba, 2012). Applied to every axis of every sensor in an INS, this leads to 24 GM parameters. AV is used to determine the random walk noise component of each INS reading, leading to six values (Quinchia et al., 2013). In the standard Kalman filter equations shown in Equations (1) and (2), GM standard deviation values are used in the noise shaping matrix G, GM time constant parameters are used in the transition matrix F (Φ in discrete time form), and INS random walk parameters are used in the process noise covariance matrix Q (combined with the G matrix to form Qd = GQGT (Farrell, 2008)).
The tunable parameters used in the EKF include the random walk components and GM time constant and variance for the scale factor and bias of the gyroscope and accelerometer. The receiver clock bias and drift random walk (Qd matrix) and a scale factor for the variance of all satellite range readings (R matrix) are the tunable parameters relating to the GNSS, leading to a total of 33 tuning parameters. Equation sets (1), the prediction step, and (2), the update step, highlight the terms where the tuning parameters are used.
1
2
where is the predicted state before correction, Φk,k−1 is the transition matrix from epoch k-1 to k, Gk−1 is the noise shaping matrix, wk−1 is the zero-mean system noise with covariance Qk−1, vk is the zero-mean measurement noise of covariance Rk, Hk is the measurement design matrix, is the predicted state error covariance matrix, Qk−1 is the process noise covariance matrix, is the observations (measurements), and zk is the innovation sequence.
2.2 Extended Kalman filter for tightly coupled IMU/GNSS
A 3D tightly coupled IMU/GNSS EKF system consists of determining the range and range rate measurements between each satellite and the receiver using IMU-calculated (mechanization equations) position and velocity and the satellites’ position and velocities calculated from the ephemeris data. The residual is then computed as the difference between the predicted range values and those directly measured by the receiver. The states of the filter consist of the position, velocity, orientation, biases/scale factors of the IMU sensor, and the GNSS receiver clock bias and drift (Atia, 2018). The IMU sensor errors are modeled by random walk components, time-varying biases, and scale factors modeled by Gauss-Markov random processes. The GNSS receiver clock bias and drift are modeled with random walk components. The pseudorange measurement noises are characterized with standard deviation estimated by the GNSS receiver and scaled by a tunable parameter value tuned by the proposed framework. A block diagram of a tightly coupled IMU/GNSS EKF is included in Figure 3.
To initialize the filter in this experiment, the initial position, velocity, and orientation states are set to the ground-truth solution provided by a separate high-end system. The GA provides tuned values for the Q and R matrices, and the initial values of the P matrix are chosen empirically. This removes the need for the tedious task of hand tuning the Q and R matrix parameters.
2.3 Practical implementation of EKF using Bierman-Thornton algorithm
The direct implementation of the EKF equations in (1-2) may lead to numerical instability where the P matrix positive definiteness feature is compromised. In our work, in propagating and updating the covariance matrix, P, consideration has been made to guarantee its positive definiteness by following the Bierman and Thornton U-D covariance factorization method described in Chiu and O’Keffe (2008) and Bierman and Thornton (1977). In Bierman-Thornton, the error covariance matrix P is represented by P = UDUT, where U is an upper triangular matrix with 1s on the diagonal and D is a diagonal matrix. This implementation is known for its numerical stability and its preservation of the symmetry and positive definiteness of the error covariance matrix P. Under the Bierman-Thornton algorithm, initially, the matrix and matrix are decomposed into the upper triangle matrix and diagonal matrix such that
3
4
Then, the time update of the P matrix is given by
5
Since all terms of this equation are decomposed into upper and diagonal matrices, the new time-propagated and matrices are calculated using the Bierman-Thornton orthogonalization algorithm described in Thornton and Bierman (1975). Since measurements are independent (satellite range measurements in our case), the measurement update is performed sequentially. The Kalman gain column vector corresponding to the ith measurement is given by
6
where is the row vector, is the scalar innovation sequence value, and is the measurement noise covariance corresponding to the ith measurement. The updated state is then calculated as follows (Chiu & O’Keffe, 2008):
7
where M is the number of measurements. The updated covariance matrix can be calculated recursively as follows (Chiu & O’Keffe, 2008):
8
In our implementation, we used the MATLAB Bierman-Thornton implementation package developed by Brian Moore, which can be downloaded from Moore (2012). The Bierman-Thornton implementation provides numerical stability, which in turn leads to better accuracy as well.
The datasets used in this paper were collected in an open-sky condition; however, before using the residuals of individual satellites for the EKF update, a statistical test using chi-squared distribution is applied to discard outlier measurements, which might occur as the result of multi-path or non-line-of-sight situations in poorly covered areas. The chi-squared test is a commonly used test to check if the observations are justifiable by a hypothesis (Cochran, 1952). The chi-squared statistic with m degree of freedom can be calculated by
9
where is the EKF residual of the ith satellite and si = Hi PHiT + Ri is the corresponding measurement prediction covariance. In this experiment, to separate inliers from outliers, the chi-square statistics of individual measurements are compared with a critical value corresponding to 90% of the chi-squared cumulative density function with one degree of freedom.
2.4 Genetic algorithms
GA are well suited for the large search space and complex relationships of the EKF parameters. This GA is used to optimize the performance of the EKF, which is represented by minimizing a fitness function. The fitness function takes an input in the form of a set of the EKF parameters and uses these parameters in the EKF to estimate a trajectory. The corresponding position, velocity, and attitude ground-truth solution for the trajectory is provided by a separate high-end INS/GNSS system, further described below. After the collection of both raw data and ground truth, the EKF tuning process is done offline. The difference between the EKF estimation and the known ground-truth trajectory is used to produce the Root Mean Square Error (RMSE) of each state estimation. The RMSE of each state is then used as a measure of the fitness of the set of EKF parameters. The process of the GA starts with generating a population of parameter sets uniformly distributed between bounds. The upper and lower bounds are empirically selected to leniently encompass all feasible values of the parameters, and the population is set to 1,000, chosen through trial and error. Each parameter set is evaluated by the fitness function and ranked according to fitness. Next, two parents are selected with a probability based on their fitness value and reproduce offspring by the two-point crossover function. The two-point crossover technique selects two random locations in the parameter list for the parent delivering the parameters to switch. Some parents have their parameters randomly mutated by a small amount to increase diversity, allowing the algorithm to increase the search space. Crossover happens until the new generation is of the desired population size, from which the cycle repeats until the convergence of the population and best fitness is achieved. A standard GA run over 25 generations for this experiment is shown in Figure 4.
2.5 Design of experiments
The DoE technique is desired to improve the behavior of the GA. With 33 tunable parameters, a GA scheme would require a massive population size to cover acceptable search spaces. However, the tuning of many of these parameters does little to improve the performance of the EKF. The DoE technique identifies high impact parameters, which are then chosen to be selectively tuned in the GA, resulting in a smaller search space and more efficient optimization effort. The DoE technique consists of assigning each parameter a high and low value determined by adding and subtracting 10% of the nominal value from itself, then evaluating the EKF fitness function with all combinations of high and low parameter values of every parameter. The slope of the variation between a single high and low parameter indicates its relative impact and is calculated by taking the average of the fitness from all instances of using the high value of the parameter of interest and subtracting the average of all fitness values resulting from using the low value of that parameter. A steep slope indicates that the parameter strongly affects the RMSE, and a shallow slope indicates that the parameter does not have much effect on the RMSE. The DoE technique produces a list of parameters and their relative slope, or impact. One method of applying these impacts to the GA is to set the GA to tune the high impact parameters for a small number of generations, and then tune the rest of the parameters in the later generations to achieve all possible small gains. This allows for quick gains in the initial tuning, then slower fine tuning after the significant parameters are tuned.
3 EXPERIMENTAL DESIGN
INS and GNSS raw data was gathered using an Invensense MPU 9250 IMU and a Novatel ProPak 6 receive (NovAtel, n.d.; InvenSense, 2016). Data was logged and synchronized on an embedded platform implemented on a NVIDIA Jetson TX2 board as seen in Figure 5. The ground-truth solution was obtained by a Novatel SPAN unit on OEM6 with a KVH1750 IMU. The sensors were mounted on a standard vehicle as shown in Figure 5. To account for a possible lever arm between the IMU and GNSS antenna, the pseudorange measurements are modified to be the range between the satellite position, as found from the Novatel GNSS receiver ephemeris, and the ground-truth Novatel position, which references the IMU position. Misalignment in the orientation of the Invensense IMU and Novatel unit was estimated by watching the consistent non-zero EKF mean errors in orientation estimations of earlier experiments. The mean of the consistent non-zero orientation shift was taken as the orientation offset between the IMU and vehicle body frame. The misalignment was then corrected by projecting all raw IMU data to the vehicle body frame through the orientation offset. After correcting the misalignment, all errors became zero-mean as will be shown in the results section. The experimental vehicle is the self-driving car platform operated by the QNX company (Ottawa-based). Data was collected by driving a 17.5-km route with several stops, turns, and straight sections. A portion of the route, shown in Figure 6, is used for the GA tuning (tuning trajectory). Two other trajectories were used as testing trajectories to verify the performance of the tuned filter. In addition to the vehicle test, a seven-hour stationary dataset for the INS was collected for noise modeling.
The data is then processed, and the experiment is run using the following process:
Gauss-Markov and Allan Variance methods are used on the stationary dataset to obtain an initial set of noise parameters called the “nominal design point.”
The nominal design point is evaluated by estimating a trajectory using the parameters and comparing the estimation with the known ground truth.
The GA is then run with the fitness function to produce a GA-tuned set of parameters.
The GA-tuned parameters are evaluated in the same process as the nominal parameters.
The EKF around the nominal design point is analyzed using DoE techniques to identify the impact each parameter contributes.
The GA iterations are applied with the DoE impact results being used in the following modifications:
The first four GA generations are processed where only the six most impactful parameters are tuned.
The population resulting after these iterations are then tuned, with the 12 most impactful parameters being varied, for six further generations.
The resulting population, after 12 generations, then has all 33 parameters tuned, and iterations are terminated when no further significant improvements are obtained.
3.1 Simulation Data
Simulation data was obtained by applying inverse kinematics on the ground-truth data. Performing inverse kinematics on the ground-truth pose trajectory allows for noise-free raw data and exact ground-truth state estimation. In addition, noise with known parameters can be injected into the inverse kinematics calculated raw data, allowing for the analysis of the hidden state estimations such as IMU biases. The experiment was run with simulated raw data along with real data to confirm that the addition of environmental noise and imperfections did not affect the tuning process.
3.2 Real data
The real dataset was collected in the field using an MPU 9250 IMU and Novatel Propak6 GNSS system mounted on a ground vehicle where ground-truth data is recorded with the Novatel Propak6 equipped with an OEM6 GNSS receiver, KVH1750 IMU (KVH, n.d.), and utilizing the RTK technology of the Propak6 SPAN unit.
4 RESULTS
4.1 Nominal design point
First, GM and AV methods are applied to find the nominal design point. From the autocorrelation function of a seven-hour stationary IMU data recording, the GM bias time constants and standard deviation are calculated and displayed in Table 1. The AV random walk is also displayed in Table 1. For the rest of the parameters, values were tuned manually by trial and error over a few iterations.
4.2 Nominal, GA, and GA with DoE experiments
The above nominal values are then used with the EKF to estimate the trajectory. The performance results in RMSE are displayed in Table 2, and the error plots for the simulated and real data are displayed in Figure 7.
The GA is then run to tune all parameters with Figure 8 displaying over ten different runs of the GA on the simulated and real data to display the variance of the results.
Using the MATLAB GA function with the population set to 1,000 and the crossover function set to the two-point crossover, the GA-tuned EKF performed significantly better than that of the nominal EKF. In the simulated and real results shown in Figure 9 and Table 3, GA tuning provided significant improvements to the heading divergence that the nominally tuned EKF produced.
Using the DoE technique described, the impact factors of each parameter are then calculated and displayed in Figure 10.
In the tuning of the high impact parameters, restricting the parameter values to only contain impactful parameters ensures that the high impact parameters are always diversified whereas allowing all parameters to be tuned may result in low impact parameters being diversified, which is not a useful operation. However, the complex relationships between the parameters may cause the impact of parameters to change, and thus even low impact parameters may eventually need to be tuned. To this end, the GA was performed, as explained earlier, to tune the top few impactful parameters for a small number of generations first. Following this, more parameters were allowed to be tuned as generations continued. Eventually, all parameters are tuned. The rationale behind these steps is that at first, tuning the high impact parameters will result in large improvements in the error. As these improvements start to level off, more lower impact parameters are allowed to be fine tuned. The results of this, as shown in Figure 11, are that the DOE stepped GA resulted in a more consistent, overall lower error and steeper convergence tuning path compared to the regular GA.
Table 4 and Figure 12 show that the DoE enhanced GA-tuned trajectory estimations are similar to those of the regular GA RMSE results. We also compare the EKF accuracy against the GNSS-only solution (Single-Point L1 solution) in Table 4. The EKF solution is approximately 92% better than the raw GNSS L1 Single-Point solution. To further validate the tuned EKF performance, we compared the estimated biases to the pre-known biases that were added to the simulated IMU data, and the results are shown in Figure 13, displaying nice bias estimation for both accelerometer (right figure) and gyroscope (left figure).
4.3 Filter validation
Several measures of EKF validation are done to confirm that the tuned parameters allow the EKF to properly model sensor biases and converge to accurate estimations for multiple trajectories that have not been used in the tuning and have not been seen by the filter before to check for overfitting. Using a DoE tuned parameter set generated from the previous experiment, the performance results of an EKF estimation for two other trajectories are shown in this section. To distinguish the datasets, the dataset used to tune the parameters with the GA in the previous section will be called the “tuning dataset,” and the two new datasets will be called “test set #1” and “test set #2”. Information about these datasets are displayed in Table 5, and trajectories are shown in Figure 14 and Figure 15.
Table 6 and Figures 16 and 17 show the pose errors of using tuned parameters in the EKF for test sets #1 and #2. The parameters used have been tuned by the GA with DoE enhancement on the tuning dataset only. The low error shows that the tuned EKF performs well for a variety of trajectories in addition to the dataset used to tune the parameters, which verifies that there is no overfitting and the tuned filter can be used for other datasets that have not been used in the tuning process.
To further demonstrate the filter health, innovation sequences and the estimated IMU biases are displayed. The EKF innovations show the difference between estimated and measured satellite ranges. Innovations should be approximately white noise and zero mean. Figures 18–20 show the innovations for the three datasets. Note that breaks appear in the plots when satellites lose visibility. Although the innovation is well within 0.4 m, which is typical for this MEMS grade IMU and non-differential GNSS, there are some residuals oscillations within the 0.3 error bound that can be seen in Figure 19. This indicates that some parameters (scale factor, biases, or time constants) may not be optimally tuned since GA, by definition, are suboptimal optimization techniques.
The sensor bias estimates are plotted in Figures 21–23 to reveal the extent to which the estimates converge. The gyroscope and accelerometer X and Y values converge well, while the accelerometer Z values approximately converge.
To further evaluate the proposed tuning technique, horizontal position RMSE under partial or complete outage with respect to the number of visible satellites, traveled distance, and outage duration is shown in Figure 24. Outage scenarios were designed with different durations (10 to 30 seconds with 5 seconds increment steps) and different numbers of visible satellites (0 to 4). Each outage scenario was repeated ten times on different regions of the dataset, and the mean was recorded. As expected, compared to complete outage, observing even a single satellite considerably contributes in bounding the error growth. Only under complete outage, non-holonomic constraints of the vehicle were applied.
4.4 Design of experiments impact
A critical aspect of the DoE impacting the GA is the validity of the DoE technique on different parameter configurations. In the current experiment, the DoE impacts were calculated using the nominal parameters. This does not consider the potential changes in the parameter impact over different parameter configurations. To explore this, multiple parameter configurations were generated by randomly perturbing the nominal parameters and sets of GA-tuned parameters. The DoE technique was then performed on these different sets to understand if the impactful parameters are consistent or if they depend on the overall parameter configuration. Figure 25 shows the impact levels of each parameter for 13 different runs with the blue bar graph in the background displaying the simulation DoE values used in the previous experiments. What can be seen is that each parameters’ impact does follow a trend to some degree. Parameters 16 and 33 show consistent impact, but parameters 4, 27, and 32 are spread out and have a wide range of possible impacts.
The DOE parameters chosen for the experimental results mostly follow the trend, but the parameter impacts are difficult to predict. Such a plot may reveal the extent of the enhancement the DoE technique provides to the GA, where plots that have highly concentrated impacts mean that the DoE effectively enhances the GA, and plots with spread out impacts indicate that the DoE less effectively enhances the GA. Future works may consider the information in this plot to produce a more adaptive GA tuning scheme.
Another analysis that shows some portions of the shape of the error function is demonstrated. The analysis consisted of plotting the variation of a single parameter vs the fitness RMSE for 50 randomly chosen parameter configurations (involving all parameters except the varying parameter). The results of this analysis, for six different parameters, are shown in Figures 26 and 27 below. In the following analysis, parameter 2 is the random walk of accelerometer y, parameter 3 is the random walk of accelerometer z, parameter 10 is the Gauss-Markov scale factor standard deviation of accelerometer x, parameter 17 is the random walk of gyroscope y, parameter 26 is the Gauss-Markov scale factor standard deviation of gyroscope y, and parameter 33 is the noise covariance matrix scale for the GNSS pseudorange measurements.
In this procedure, using parameter 2 as the example, 32 other parameters are first randomized to take any value within their respective bounds. Note that many lower bounds are significantly small values resulting in plots showing near-zero values on the x-axis. Then, parameter 2 is varied from its lower bound to its upper bound, and the RMSE of the 32 randomized parameters and the value of parameter 2 are plotted, creating one line. This is repeated for 6 different selected parameters and 50 different randomized parameter configurations with the resulting plot of 50 lines for each 6 parameters being shown in Figure 26, which shows all the resulting lines, and Figure 27, which shows the plot zoomed into relevant lines as discussed below.
In Figure 26, there are two clear zones where the vast majority of lines belong on a y-value near 260 or 10. Values belonging in the high RMSE zone are solely due to parameter 33 being outside of its own low error zone, between roughly 0.5 and 6.5, seen in the bottom right plot of both figures. The high RMSE lines are thus ruled out to be not relevant to the analysis, so the focus is on the low RMSE lines.
These graphs illustrate how the variation of parameters tend to change when other parameters are changed. Parameters 10 and 26 are shown to be fixed over any value they take, demonstrating that some parameters do not need significant variations. Parameters 2, 3, and 17 show a varying degree of fluctuation that may affect the RMSE in the order of 10–20 points, and parameter 33 shows a case of a critical tuning parameter with high impact. The lines in the graph for parameter 33 are also consistent with the lines of different parameter configurations, which supports the results from Figure 25 showing that parameter 33 impacts are concentrated.
Based on the experimental results and the analysis, the DoE technique in this situation provides more consistency and gives some performance improvements in the GA due to the significance of parameters being somewhat consistent throughout the tuning process. The DoE analysis plots can be used to determine the effectiveness of the DoE technique and can reveal details on how each parameter impacts the RMSE, such as where constant zones and steep slopes are located. In systems where the DOE significance plots are highly concentrated and where the plots shown in Figure 26 have consistent variation, it can be assumed that the tuning of the DoE parameters will have a much higher impact on the GA.
5 CONCLUSION
This work demonstrated an efficient tuning framework for the EKF with an application to a tightly coupled IMU/GNSS integrated navigation system. The work binds conventional stochastic modeling techniques with GA and DoE methods in an innovative way to quickly obtain a more accurate EKF. Physical field data was collected on a self-driving car platform from BlackberryQNX equipped with a high-end ground-truth navigation system and low-cost MEMS IMU. The EKF filter implementation followed the Bierman-Thornton U-D covariance factorization technique for better numerical stability. Experimental results showed that the nominal parameters can be used as good initial parameters but the GA tuning significantly improved performance. Finally, the DoE enhancement consistently improved the convergence behavior of the GA.
HOW TO CITE THIS ARTICLE
Zhang A, Atia MM. An efficient tuning framework for Kalman filter parameter optimization using design of experiments and genetic algorithms. NAVIGATION. 2020;67:775–793. https://doi.org/10.1002/navi.399
ACKNOWLEDGMENTS
We would like to thank Mr. David van Geyn and QNX Ottawa for their support in facilitating the field experiments and data collection essential to this work. This work was funded by NSERC Discovery Grant: RGPIN-2017-06261.
Footnotes
Funding information
Natural Sciences and Engineering Research Council of Canada, Grant/Award Number: RGPIN-2017-06261
- Received November 6, 2019.
- Revision received July 3, 2020.
- Accepted September 7, 2020.
- Copyright © 2020 Institute of Navigation
This is an open access article under the terms of the Creative Commons Attribution License, which permits use, distribution and reproduction in any medium, provided the original work is properly cited.