Next Article in Journal
An Indoor Positioning System Based on Static Objects in Large Indoor Scenes by Using Smartphone Cameras
Next Article in Special Issue
Non-GNSS Smartphone Pedestrian Navigation Using Barometric Elevation and Digital Map-Matching
Previous Article in Journal
Expert System for Monitoring the Malaxing State of the Olive Paste Based on Computer Vision
Previous Article in Special Issue
Huber’s Non-Linearity for GNSS Interference Mitigation
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

GNSS/INS Fusion with Virtual Lever-Arm Measurements

Department of Mapping and Geo-Information Engineering, Technion–Israel Institute of Technology, Haifa 3200003, Israel
*
Author to whom correspondence should be addressed.
Sensors 2018, 18(7), 2228; https://doi.org/10.3390/s18072228
Submission received: 15 June 2018 / Revised: 6 July 2018 / Accepted: 7 July 2018 / Published: 11 July 2018
(This article belongs to the Special Issue GNSS and Fusion with Other Sensors)

Abstract

:
The navigation subsystem in most platforms is based on an inertial navigation system (INS). Regardless of the INS grade, its navigation solution drifts in time. To avoid such a drift, the INS is fused with external sensor measurements such as a global navigation satellite system (GNSS). Recent publications showed that the lever-arm, defined as the relative position between the INS and aiding sensor, has a strong influence on navigation accuracy. Most research in this field is focused on INS/GNSS fusion with GNSS position or velocity updates while considering various maneuvers types. In this paper, we propose to employ virtual lever-arm (VLA) measurements to improve the accuracy and time to convergence of the observable INS error-states. In particular, we show that VLA measurements improve performance even in stationary conditions. In situations when maneuvering helps to improve state observability, VLA measurements manage to gain additional improvement in accuracy. These results are supported by simulation and field experiments with a vehicle mounted with a GNSS and an INS.

1. Introduction

Inertial navigation system (INS) and global positioning satellite system (GNSS) fusion aims to utilize the advantages of the two individual systems and overcome their weaknesses. To that end, several coupling architectures for INS/GNSS integration have been proposed. Among them are the loosely coupled (LC) and tightly coupled (TC) approaches [1,2]. In LC integration, both the GNSS and INS operate autonomously to yield their state solution followed by an INS/GNSS integrated solution. Firstly, the raw GNSS measurements are inserted into a standalone GNSS filter to calculate the position and velocity vectors of the GNSS receiver. This GNSS solution is used in aiding the INS filter in a decentralized implementation to estimate the platform states.
In contrast to the LC approach, the TC approach forms an INS/GNSS centralized filter that does not separate the GNSS and INS navigation solutions. The raw GNSS measurements, which are the pseudorange and pseudorange rate, together with those constructed using the INS solution are combined to form the measurements used in the navigation filter [3]. The TC approach provides a more accurate solution than the LC approach as the raw GNSS measurements (pseudorange and pseudorange rate) are introduced directly to the navigation filter [4,5].
In practice, the LC approach [6,7] is more popular since it offers greater flexibility and modularity in terms of system implementation as it allows the use of off-the-shelf hardware that can be easily assembled. In spite of its popularity, the LC approach has a major disadvantage since it requires four or more satellites to form a GNSS position/velocity solution required for the navigation filter. If less than four satellites are available, the navigation solution will rely solely on the standalone INS solution, which, regardless of its grade, drifts in time. There are several solutions to such situations such as the modified loosely coupled approach [8]. This approach makes use of fictitious satellites based on known satellites trajectories and previous vehicle navigation solutions are constructed to enable a pseudo-GNSS solution to aid the INS.
Both LC and TC approaches are widely used in INS/GNSS integrated navigation solutions. As seen in Reference [9], both methods were tested and compared under the goal of achieving continuous and reliable navigation data for vehicles in urban areas. As seen in References [10,11,12], the TC approach was used to enhance ambiguity resolution (AR) for precise GNSS positioning in real time kinematic (RTK) applications, while in References [13,14,15] the TC approach was utilized to obtain a more reliable navigation and attitude determination for lightweight unmanned aerial vehicles (UAVs) using onboard low-cost equipment. In References [16,17], the LC approach was used to enhance georeferencing accuracy for dynamic platforms.
Regardless of the integration approach, the lever-arm between the GNSS receiver (usually mounted on the outside surface of the platform) and INS (usually mounted inside the platform) should be taken into account while calculating the navigation solution. At first, that problem was tackled by considering the lever-arm in the GNSS measurement matrix for position-aided INS [18] or for velocity-aided INS [19]. In that manner, the INS error-state model, commonly the 15 error-state model [7], which is used as the system model for the navigation filter, is left unchanged.
However, due to the locations of the two systems, in practice, it is difficult to accurately measure the lever-arm. In such situations, the lever-arm error will degrade the accuracy of the navigation solution [20,21]. To that end, it was suggested [21] to use the lever-arm error as additional error-states in the navigation filter and thereby increasing the state dimension to 18. Using such an error-state model, an observability analysis of LC INS/GNSS approach was made examining the influence of vehicle maneuvers [22,23].
In this paper, we propose to use a virtual lever-arm (VLA) measurement in addition to a GNSS position or velocity measurements to aid the INS. The motivation for virtual lever-arm measurement is to improve LC approach performance in terms of accuracy and time to converge to steady state solution. The basic idea behind VLA measurement is that, in practice, the lever-arm is known to some accuracy level; however, this knowledge is not utilized directly in the navigation filter, whereas, in some contexts, only to model the stochastic process describing the lever-arm error characteristics. By introducing VLA we utilize this knowledge directly to improve the navigation performance.
The use of virtual measurements, that is translating external knowable on the platform or its operating environment into external measurement to the navigation filter, was proven to be very useful in navigation applications. Nonholonomic constraints in land vehicle navigation [24,25] that translate the fact that the vehicle is travelling on a road and experiences velocity directed only in its longitudinal axis were used as virtual velocity aiding. In addition, zero velocity updates are commonly used in shoe-mounted indoor navigation [26]. At each instance where it is recognized that the foot is resting on the ground, a virtual zero velocity measurement is introduced into the navigation filter.
The VLA measurement is derived in the paper and used to evaluate the INS/GNSS LC navigation filter for different error-state models given the platform dynamics. In particular, we consider here two error-state models: (1) the 18 error-state model to include the lever-arm errors with position measurements; and (2) the 15 error-state model to include the lever-arm states with velocity measurements (the position error-states are not observable and therefore are omitted). A comparison is made between these two models with and without VLA. Both a simulation and a field experiment were used to evaluate the contribution of the virtual lever-arm approach to enhance error-states’ estimation performance.
The rest of the paper is organized as follows: Section 2 presents the navigation equation together with the measurement matrix development for the velocity and the position aided models. Section 3 presents experimental results from numerical simulation tests that examined the VLA contribution to the different models. Section 4 aims to check the findings from the numerical simulation with results from a field test with real data.

2. Navigation Equations

In this section the navigation equations of motion, error-state models, and the measurement model used in this paper are introduced.

2.1. Kinematic Equations of Motion

The local navigation reference frame was used to represent the position, velocity, and attitude misalignment, while the accelerometer and gyro residuals, modeled as constant bias process, are expressed in the body reference frame. The navigation equations in the navigation frame are [2,7]:
P ˙ n = V n ,
V ˙ n = T b n f i b b + g n ( Ω e n n + 2 Ω i e n ) V n ,
T ˙ b n = T b n Ω i b b ( Ω i e n + Ω e n n ) T b n ,
where P n and V n are position and velocity vectors expressed in the navigation frame, g n is the gravitation vector, T b n is the transformation matrix from body to navigation frame, f i b b and Ω i b b are the specific force and skew-symmetric matrix of the angular velocity vector expressed in the body frame, and subscripts ‘i’ and ‘e’ were occasionally used to refer to the inertial frame and the Earth-Centered Earth-Fixed (ECEF) frame, respectively.

2.2. Error-State Models

To derive the error-state model, the following error definitions were applied:
P ^ n = P n + δ P n ,
V ^ n = V n + δ V n ,
T ^ b n = ( I + [ γ n × ] ) T b n ,
f ^ i b b = f i b b + ε a + w a ,
ω ^ i b b = ω i b b + ε g + w g ,
l ^ b = l b + δ l b ,
where δ P n and δ V n are the position and velocity errors vectors, respectively, γ n is the attitude misalignment vector and [ γ n × ] is the skew-symmetric matrix of γ n , f ^ i b b and ω ^ i b b are the specific force and gyro measurements, ε a and w a are the accelerometer bias and zero mean Gaussian white noise, ε g and w g are the gyro bias and zero mean Gaussian white noise, and l b is the lever-arm vector expressed in the body frame. The system dynamics can be written in matrix form as
δ x ˙ = A δ x + G w ,
where δ x is the error-state vector, A is the system matrix, w is the system noise vector, and G is the system noise distribution matrix. In this paper, two error-state models are implemented, one for position aiding and one for velocity aiding as addressed in the following subsections.

2.2.1. 15 Error-State Model

The 15 error-state model was derived to describe a velocity-aided INS with lever-arm vector between the INS and aiding sensor. In this case, the error-state model consists of velocity, attitude, accelerometer, and gyro bias residuals and lever-arm error-states. The position error-states are omitted from the state space model since they are not observable from velocity measurements [27].
When assuming constant biases, the corresponding linear model is given by [1]:
δ V ˙ n = [ T b n f i b b × ] γ n + T b n ε a + T b n w a ,
γ ˙ n = T b n Ω i b b T b n T γ n + T b n ε g + T b n w g ,
ε ˙ a = 0 ,
ε ˙ g = 0 ,
δ l ˙ b = 0 .
The error-state vector is then
δ x 15 = [ δ V γ ε a ε g δ l ] T ,
and the corresponding system dynamics and shaping matrix are
A 15 = [ 0 3 × 3 [ T b n f i b b × ] T b n 0 3 × 3 0 3 × 3 0 3 × 3 T b n Ω i b b T b n T 0 3 × 3 T b n 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 ] ,
G 15 = [ T b n 0 3 × 3 0 3 × 3 T b n 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 ] .

2.2.2. 18 Error-State Model

The 18 error-state model was derived to describe lever-arm-aided INS with position updates. The 18 error-state model includes all the error-states from the 15 error-state model augmented with the position error-state vector. The model shares the same navigation equations and dynamic linear model as in 15 error-state model (Section 2.2.1), with addition of terms regarding the position error.
The additional position error-states are modeled by
δ P ˙ n = δ V n ,
the error-state vector, for position-aided INS, is then
δ x 18 = [ δ P δ V γ ε a ε g δ l ] T ,
and the system and shaping matrix are
A 18 = [ 0 3 × 3 I 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 [ T b n f i b b × ] T b n 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 T b n Ω i b b T b n T 0 3 × 3 T b n 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 ] ,
G 18 = [ 0 3 × 3 0 3 × 3 T b n 0 3 × 3 0 3 × 3 T b n 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 ] .

2.3. Measurement Model

We consider a typical scenario of aided INS, where a lever-arm vector exists between the two sensors as illustrated in Figure 1. It is assumed that the body reference frame coincides with the inertial sensors sensitive axes and that the lever-arm vector is expressed in the body reference frame. Lever-arm to the measurement sensor may result from the position constraints of the sensor—like open sky for a GNSS antenna. This type of lever-arm may contain values of several meters, especially on large platforms, such as aircrafts or boats, and therefore has a high influence on the navigation solution accuracy [28].
The measurement model can be written as
δ z = H δ x + v ,
where δ z is the measurement’s residual vector, H is the measurement’s design matrix and v is the measurement noise.
In the following sections, this model was developed, and the measurement matrix H was described for two measurement aiding sensors—position and velocity. In both aiding methods, the error-state model was augmented with the lever-arm error-states, which reflects that the lever-arm is not considered to be constant. This model is useful if the lever-arm elements are hard to evaluate in a satisfying accuracy and it will be used here for the implementation of the VLA for the performance analysis. The appearance of VLA measurement component in the measurement matrix is shown next.

2.3.1. Velocity Aiding

Consider a velocity measurement with a lever-arm vector relative to INS as shown in Figure 1, were l b is the lever-arm. These velocity measurements can be modeled as [28]:
V 1 n = V n + T b n [ ω i b b × ] l b ,
where V 1 n is the velocity measurement vector containing a lever-arm. Let the measurement residual, the difference between the INS-based velocity and measured velocity, be
δ V 1 n = V ^ 1 n V 1 n .
Then, combining Equations (5)–(9) and Equation (24), we obtain
δ V 1 n = δ V n + ( I + [ γ n × ] ) T b n ( ω i b b + ε g ) × ( l b + δ l b ) T b n ω i b b × l b .
After rearranging and eliminating 2nd order error elements, Equation (26) reduces to
δ V 1 n = δ V n [ T b n ( ω i b b × ) l b × ] γ n T b n [ l b × ] ε g + T b n ω i b b × δ l b .
Let L b = [ l b × ] and Ω i b b = [ ω i b b × ] , so that the velocity measurement estimation error can be written as:
δ V 1 n = δ V n [ T b n Ω i b b l b × ] γ n T b n L b ε g + T b n Ω i b b δ l b .
Thus, the measurement matrix for a 15 error-state vector velocity-aided INS in Equation (23) is
H 15 = [ I 3 × 3 ( T b n Ω i b b l b × ) 0 3 × 3 T b n L b T b n Ω i b b ] .

2.3.2. Position Aiding

Herein, instead of velocity aided INS we consider a position measurement with lever-arm-aided INS. Position measurements with lever-arm can be modeled as [21]:
P 1 n = P n + T b n l b ,
where P 1 n represents the position measurement vector with lever-arm.
Let the measurement residual, the difference between the INS-based position and the measurement position, be
δ P 1 n = P ^ 1 n P 1 n .
Then, using Equations (4)–(9) and Equation (30), we obtain
δ P 1 n = δ P n + T b n δ l b + [ γ n × ] T b n l ^ b [ γ n × ] T b n δ l b .
After rearranging and eliminating 2nd order error elements in Equation (32), the position measurement estimation error can be written as:
δ P 1 n = δ P n ( T b n l ^ b x ) γ n + T b n δ l b .
Thus, the measurement matrix for an 18 error-state vector position aided INS in Equation (23) is
H 18 = [ I 3 × 3 0 3 × 3 ( T b n l ^ b x ) 0 3 × 3 0 3 × 3 T b n ] .

2.3.3. Virtual Lever-Arm Measurements

In order to control the lever-armed system performance, we propose the VLA measurement approach. In general, the lever-arm is known up to some level of confidence, which usually decreases for bigger platforms. However, in most situations this lever-arm remains fixed. The VLA concept takes advantage of that knowledge and translates it into virtual measurements to the navigation filter.
For example, suppose the true lever-arm vector is one meter in each axis. However, due to mechanical constraints, it can be measured up to an accuracy of one centimeter in each axis. Thus, we can assume a virtual sensor measuring the unknown lever-arm error with an accuracy of centimeter. As we show in the results section, this concept helps to improve the navigation performance.
After explaining the basic idea of VLA, we turn to derive the virtual measurement. The VLA measurement residual can be model as
δ l 1 b = l ^ b l b ,
where l ^ b is the lever-arm virtual measurement vector and l b is the known lever-arm value (such as one meter in our pervious example). Combining Equation (9) with Equation (35) we obtain
δ l 1 b = δ l b ,
which results in the following measurement matrix, presented here for the 15 (velocity-aided) and 18 (position-aided) error-state models:
H 15 _ V L A = [ 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 I 3 × 3 ] ,
H 18 _ V L A = [ 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 0 3 × 3 I 3 × 3 ] .
Augmenting the VLA measurement matrix with a velocity or position measurement matrix, reflected in Equations (29) and (34), respectively, results in the following measurement matrices for the velocity- and position-aided system with VLA measurements:
H 15 _ C o m b i n e d = [ I 3 × 3 ( T b n Ω i b b l b × ) 0 3 × 3 T b n L b T b n Ω i b b 0 3 × 3               0 3 × 3        0 3 × 3      0 3 × 3 I 3 × 3 ] ,
H 18 _ C o m b i n e d = [ I 3 × 3 0 3 × 3        ( T b n l ^ b x )    0 3 × 3 0 3 × 3   T b n 0 3 × 3 0 3 × 3               0 3 × 3        0 3 × 3 0 3 × 3 I 3 × 3 ] .
To summarize, instead of using the classical measurement matrix model for velocity (Equation (29)) and position (Equation (34)) aiding, we propose to use them with augmented VLA measurements as in Equation (39) for velocity aiding and Equation (40) for position aiding.

3. Simulation Results

To test the performance of the different models, a comprehensive GNSS/INS numerical simulation was constructed. A low-grade IMU (Inertial Measurement Unit) sensor was simulated with an update rate of 100 Hz. The INS solution was corrected with an EKF (Extended Kalman Filter) at 1 Hz using the velocity or position measurements. All measurements were modeled as zero mean Gaussian white noise. The standard deviation (STD) of the position and velocity measurements noise was set to 1 m and 0.8 m/s, respectively. Lever-arm elements were set to [1 1 1] in meters in the body frame. For the VLA measurements, a noise STD was set to 1 mm. The accelerometer constant bias was set to [0.1 0.1 0.1] with noise STD of 0.01 in m/s2. The gyro constant bias was set to [10 10 10] with noise STD of 1 in °/h.
The simulation was implemented for a scenario of 120 s and tested with three types of maneuvers in piecewise linear motion—in the first 40 s the system was in stationary conditions, between 40 to 80 s the system accelerated in X body axis direction, and from 80 to 120 s the system was rotated around the Z axis. The resulting STDs of the error-state covariance for the 15 and 18 error-state models are summarized in Figure 2 and Figure 3, respectively.

3.1. Velocity-Aided Model

Figure 2 presents simulation results for a velocity-aided 15 error-state model. According to the lever-arm STD graph, without VLA measurements, the lever-arm elements are not observable for the first 80 s. From second 80, when the system starts to rotate around Z, the horizontal elements of the lever-arm convergent. VLA measurements, on the other hand, make the lever-arm component observable from the beginning. This is an expected result since the lever-arm is measured directly by the VLA measurement. However, the rest of the error-state vector is not affected in a considerable amount. Only a small improvement was detected in the accelerometer and gyro bias STD elements.
This result indicates that the lever-arm elements have a negligible influence on the system state vector when a velocity-aided state model is in use. Thus, for velocity-aided INS, the VLA measurements are not useful for the examined maneuvers.
A possible explanation for this statement can be derived from the observability properties of the lever-arm error-state elements. In Equation (28), these elements appear in the coefficient for the attitude error together with the angular velocity component. As a result, their impact on the estimation performance should be noticed when rotation is applied. Since the lever-arm elements are naturally observable in this case due to the maneuver, as shown, for example, in Figure 2, the contribution of measuring them has a small influence on performance.

3.2. Position-Aided Model

Figure 3 shows simulation results for 18 error-state model that is used for position-aided INS. For this model, the lever-arm STD graph without VLA measurements is descending in a fraction from the beginning due to the position measurement, and then remains at the same level during 80 s. Similar to the velocity-aided model, the significant convergence of the lever-arm horizontal elements occurs when the system starts to rotate around Z.
Here, the use of the VLA measurements, as it leads to an improvement in the lever-arm estimation, appears to also affect the performance of the navigation state element estimation. Similar to the velocity-aided model, an improvement was detected in the accelerometer and gyro bias STD elements, but in a more considerable amount. For the position states estimation-wise, the VLA has led to a significant improvement in the STD values in each of the tested maneuvers. A significant improvement was noticed in all three directions when the system was motionless or accelerating in X, and in the ‘Down’ direction when the system was rotating around Z. All of those improvements are related to the unobservable subspaces of the position states with a lever-arm under the different maneuvers, indicating that a VLA measurement improves position state estimation when lever-arm states are not observable in the maneuver.
Contrary to the velocity-aided model, the results here indicate that a position-aided model benefits from estimating the lever-arm elements using the VLA.

4. Field Test

To complete the performance analysis, and to verify simulation findings and conclusions, a field test was conducted. Following the results from the simulation analysis in Section 3, which showed that the lever-arm estimation influence is mostly reflected in the position state estimation for position-aided INS, the field test focused on the position estimation performance with and without VLA. Accelerometer and gyro measurements at 100 Hz from an LG-G3 smartphone were corrected with position information extracted from an external geodetic GNSS receiver (Triumph-1, Javad GNSS Inc., San Jose, CA, USA) with measurements at 1 Hz. Both smartphone and GNSS antenna were installed on top of a vehicle with a lever-arm of [0 1.8 0] meters in the smartphone body reference frame. While measuring, the different maneuvers conducted by the vehicle contain: static condition for 40 s, accelerating and driving in a straight line for 60 s, and, at last, circuited twice in a roundabout. Figure 4 presents the driving path of the vehicle and the velocity information extracted from the GNSS data.
Figure 5 presents the STD results of the position and lever-arm estimation from the field test with the position aiding model. The field experiment results have the same characteristics as the simulation results presented in Section 3.2. Without VLA, the lever-arm horizontal state estimation errors are convergent only when the vehicle starts driving in the roundabout, which can be considered as a rotation around the Z maneuver. The ‘Down’ component of the lever-arm remains on the same level once it stabilizes at the beginning. As a result, the position error-states are stabilized at about 0.8 m during the static and the one-directional motion maneuvers, and, once the vehicle starts its rotation, the horizontal errors drop to 0.4 m, while the ‘Down’ component remains at the same level.
With VLA, on the other hand, as the lever-arm states are artificially measured, all the position states are convergent to a value of 0.4 m from the beginning. This result is adequate with the findings from the simulation and strengthens the statement that VLA measurements contribute to improve navigation performance when lever-arm states are not observable in the maneuver.

5. Conclusions

In this paper, VLA measurement was proposed to improve performance of position- or velocity-aided INS. VLA was motivated by the fact that the lever-arm between the GNSS antenna and the IMU’s body frame is usually known for up to some level of confidence and should be reflected in the system to enhance navigation performance.
Numerical simulations and a field experiment with IMU/GNSS have shown that VLA measurements improve the position error-state estimation for position-aided INS. This improvement was especially noticeable in stationary conditions and in other maneuvering types that make the lever-arm elements unobservable. In addition, slight improvements were shown in the accelerometer and gyro bias estimation. On the other hand, VLA measurements did not improve velocity-aided INS and are, therefore, appropriate only for lever-arm position-aided INS.
The simulation and experiment results highlight the VLA contribution for the position-aided INS under representative maneuvering types. According to those results, future implementation of the VLA measurements in navigation applications can benefit from it in terms of the reduced position error, especially on the large-scale platforms where lever-arm components may be difficult to measure and evaluate.

Author Contributions

Formal analysis, A.B. and I.K.; Methodology, I.K.; Resources, G.E.T.; Software, A.B.; Validation, G.E.T.; Writing—original draft, A.B.; Writing—review & editing, I.K. and G.E.T.

Funding

This research received no external funding.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Titterton, D.; Weston, J.L.; Weston, J. Strapdown Inertial Navigation Technology; IET: Stevenage, UK, 2004; Volume 17. [Google Scholar]
  2. Farrell, J. Aided Navigation: GPS with High Rate Sensors; McGraw-Hill, Inc.: New York, NY, USA, 2008. [Google Scholar]
  3. Greenspan, R.L. GPS and inertial integration. Glob. Position. Syst. Theory Appl. 1996, 2, 187–220. [Google Scholar]
  4. Hide, C.; Moore, T. GPS and low cost INS integration for positioning in the urban environment. In Proceedings of the ION GPS, Long Beach, CA, USA, 13–16 September 2005; pp. 13–16. [Google Scholar]
  5. Petovello, M.G.; Cannon, M.E.; Lachapelle, G. Benefits of Using a Tactical-Grade IMU for High-Accuracy Positioning. Navigation 2004, 51, 1–12. [Google Scholar] [CrossRef]
  6. Godha, S.; Cannon, M.E. GPS/MEMS INS integrated system for navigation in urban areas. GPS Solut. 2007, 11, 193–203. [Google Scholar] [CrossRef]
  7. Groves, P.D. Principles of GNSS, Inertial, and Multisensor Integrated Navigation Systems; Artech House: Norwood, MA, USA, 2013. [Google Scholar]
  8. Klein, I.; Filin, S.; Toledo, T. A modified loosely coupled approach to INS/GPS integration. J. Appl. Geodesy 2011, 5, 87–97. [Google Scholar] [CrossRef]
  9. Yang, L.; Li, Y.; Wu, Y.; Rizos, C. An enhanced MEMS-INS/GNSS integrated system with fault detection and exclusion capability for land vehicle navigation in urban areas. GPS Solut. 2014, 18, 593–603. [Google Scholar] [CrossRef]
  10. Lee, H. An integration of GPS with INS sensors for precise long-baseline kinematic positioning. Sensors 2010, 10, 9424–9438. [Google Scholar] [CrossRef] [PubMed]
  11. Han, H.; Wang, J.; Wang, J.; Tan, X. Performance analysis on carrier phase-based tightly-coupled GPS/BDS/INS integration in GNSS degraded and denied environments. Sensors 2015, 15, 8685. [Google Scholar] [CrossRef] [PubMed]
  12. Li, T.; Zhang, H.; Niu, X.; Gao, Z. Tightly-Coupled Integration of Multi-GNSS Single-Frequency RTK and MEMS-IMU for Enhanced Positioning Performance. Sensors 2017, 17, 2462. [Google Scholar] [CrossRef] [PubMed]
  13. Petritoli, E.; Giagnacovo, T.; Leccese, F. Lightweight GNSS/IRS integrated navigation system for UAV vehicles. In Proceedings of the 2014 IEEE Metrology for Aerospace (MetroAeroSpace), Benevento, Italy, 29–30 May 2014; pp. 56–61. [Google Scholar]
  14. Eling, C.; Klingbeil, L.; Kuhlmann, H. Real-time single-frequency GPS/MEMS-IMU attitude determination of lightweight UAVs. Sensors 2015, 15, 26212. [Google Scholar] [CrossRef] [PubMed]
  15. Reimer, C.; Schneider, T.; Stock, M. INS/GNSS integration for aerobatic flight applications and aircraft motion surveying. Sensors 2017, 17, 941. [Google Scholar]
  16. Eugster, H.; Huber, F.; Nebiker, S.; Gisi, A. Integrated georeferencing of stereo image sequences captured with a stereovision mobile mapping system–approaches and practical results. ISPRS-Int. Arch. Photogramm. Remote Sens. Spatial Inf. Sci. 2012, 39, B1. [Google Scholar] [CrossRef]
  17. Jiang, W.; Li, Y.; Rizos, C. Optimal data fusion algorithm for navigation using triple integration of PPP-GNSS, INS, and terrestrial ranging system. IEEE Sens. J. 2015, 15, 5634–5644. [Google Scholar] [CrossRef]
  18. Grejner-Brzezinska, D.A.; Da, R.; Toth, C. GPS error modeling and OTF ambiguity resolution for high-accuracy GPS/INS integrated system. J. Geodesy 1998, 72, 626–638. [Google Scholar] [CrossRef]
  19. Zhao, L.; Gao, W. The experimental study on GPS/INS/DVL integration for AUV. In Proceedings of the Position Location and Navigation Symposium (PLANS 2004), Monterey, CA, USA, 26–29 April 2004; pp. 337–340. [Google Scholar]
  20. Bell, T. Error analysis of attitude measurement in robotic ground vehicle position determination. Navigation 2000, 47, 289–296. [Google Scholar] [CrossRef]
  21. Hong, S.; Chang, Y.S.; Ha, S.K.; Lee, M.H. Estimation of alignment errors in GPS/INS integration. In Proceedings of the ION GPS, Portland, OR, USA, 24–27 September 2002; pp. 24–27. [Google Scholar]
  22. Hong, S.; Lee, M.H.; Chun, H.H.; Kwon, S.H.; Speyer, J.L. Observability of error states in GPS/INS integration. IEEE Trans. Veh. Technol. 2005, 54, 731–743. [Google Scholar] [CrossRef]
  23. Hong, S.; Lee, M.H.; Chun, H.H.; Kwon, S.H.; Speyer, J.L. Experimental study on the estimation of lever arm in GPS/INS. IEEE Trans. Veh. Technol. 2006, 55, 431–448. [Google Scholar] [CrossRef]
  24. Brandt, A.; Gardner, J.F. Constrained navigation algorithms for strapdown inertial navigation systems with reduced set of sensors. In Proceedings of the American Control Conference, Philadelphia, PA, USA, 26 June 1998; pp. 1848–1852. [Google Scholar]
  25. Klein, I.; Filin, S.; Toledo, T. Pseudo-Measurements as Aiding to INS during GPS Outages. Navigation 2010, 57, 25–34. [Google Scholar] [CrossRef]
  26. Skog, I.; Nilsson, J.O.; Händel, P. Evaluation of zero-velocity detectors for foot-mounted inertial navigation systems. In Proceedings of the 2010 International Conference on Indoor Positioning and Indoor Navigation (IPIN), Zurich, Switzerland, 15–17 September 2010; pp. 1–6. [Google Scholar]
  27. Dissanayake, G.; Sukkarieh, S.; Nebot, E.; Durrant-Whyte, H. The aiding of a low-cost strapdown inertial measurement unit using vehicle model constraints for land vehicle applications. IEEE Trans. Robot. Autom. 2001, 17, 731–747. [Google Scholar] [CrossRef]
  28. Seo, J.; Lee, H.K.; Lee, J.G.; Park, C.G. Lever arm compensation for GPS/INS/odometer integrated system. Int. J. Control Autom. Syst. 2006, 4, 247–254. [Google Scholar]
Figure 1. Lever-arm-aided INS with position or velocity measurement sensor (e.g., GNSS antenna).
Figure 1. Lever-arm-aided INS with position or velocity measurement sensor (e.g., GNSS antenna).
Sensors 18 02228 g001
Figure 2. STD results from the software simulation for a velocity-aided system with and without VLA.
Figure 2. STD results from the software simulation for a velocity-aided system with and without VLA.
Sensors 18 02228 g002aSensors 18 02228 g002b
Figure 3. STD results from the software simulation for a position-aided system with and without VLA.
Figure 3. STD results from the software simulation for a position-aided system with and without VLA.
Sensors 18 02228 g003aSensors 18 02228 g003b
Figure 4. Field test properties. (a) Driving path; (b) Velocity extracted from the GNSS receiver.
Figure 4. Field test properties. (a) Driving path; (b) Velocity extracted from the GNSS receiver.
Sensors 18 02228 g004
Figure 5. STD results from the field test for position-aided model with and without VLA.
Figure 5. STD results from the field test for position-aided model with and without VLA.
Sensors 18 02228 g005

Share and Cite

MDPI and ACS Style

Borko, A.; Klein, I.; Even-Tzur, G. GNSS/INS Fusion with Virtual Lever-Arm Measurements. Sensors 2018, 18, 2228. https://doi.org/10.3390/s18072228

AMA Style

Borko A, Klein I, Even-Tzur G. GNSS/INS Fusion with Virtual Lever-Arm Measurements. Sensors. 2018; 18(7):2228. https://doi.org/10.3390/s18072228

Chicago/Turabian Style

Borko, Aviram, Itzik Klein, and Gilad Even-Tzur. 2018. "GNSS/INS Fusion with Virtual Lever-Arm Measurements" Sensors 18, no. 7: 2228. https://doi.org/10.3390/s18072228

APA Style

Borko, A., Klein, I., & Even-Tzur, G. (2018). GNSS/INS Fusion with Virtual Lever-Arm Measurements. Sensors, 18(7), 2228. https://doi.org/10.3390/s18072228

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

Article Metrics

Back to TopTop