Next Article in Journal
A Probabilistic Target Search Algorithm Based on Hierarchical Collaboration for Improving Rapidity of Drones
Next Article in Special Issue
Joint Design of Space-Time Transmit and Receive Weights for Colocated MIMO Radar
Previous Article in Journal
fPADnet: Small and Efficient Convolutional Neural Network for Presentation Attack Detection
Previous Article in Special Issue
Multiday EMG-Based Classification of Hand Motions with Deep Learning Techniques
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Gyroscope Bias Estimation Algorithm Based on Map Specific Information

School of Information Science and Engineering, Xiamen University, Xiamen 361000, China
*
Author to whom correspondence should be addressed.
Sensors 2018, 18(8), 2534; https://doi.org/10.3390/s18082534
Submission received: 30 June 2018 / Revised: 30 July 2018 / Accepted: 30 July 2018 / Published: 2 August 2018
(This article belongs to the Special Issue Sensor Signal and Information Processing)

Abstract

:
In an inertial navigation system, especially in a pedestrian dead-reckoning system, gyroscope bias can demonstrably reduce positioning accuracy. A novel gyroscope bias estimation algorithm is proposed, which estimates the bias of a gyroscope under any set of angle observations. Moreover, a method for obtaining Euler angles using map corridor information is proposed. The heading information obtained from a map is used to estimate the bias, and the estimated bias is used to correct the trajectories. Experimental results show that it is feasible for the algorithm to estimate the bias of the gyroscope.

1. Introduction

Accurate attitude information (pitch, roll, and heading angles) is an essential part of good navigation results. In various systems that rely on inertial sensors for navigation and positioning, attitude information is obtained mainly using a gyroscope. However, because of factors such as materials and manufacturing processes, the values measured by gyroscopes include errors. Especially for low-cost gyroscopes, large random errors in measurement occur [1]. Also, in long-term navigation, errors seriously impede estimation accuracy and even result in positioning being unavailable. Therefore, it is necessary to estimate and eliminate the bias of the gyroscope.
Some researchers have estimated gyroscope bias based on quaternion. Vik et al. [2] proposed a scheme to express nonlinear kinematics using quaternions. It is assumed that the bias model of the gyroscope exponentially decays, but that does not correspond to the actual situation. Boskovic et al. [3,4], proposed a quaternion-based nonlinear deviation estimator and coupled the estimator with an adaptive sliding control strategy. Because the object in these papers is a spacecraft, the motion model is more constrained. The estimator assumes that the change of attitude of the spacecraft will not exceed 180 degrees and the change cannot be applied to some situations with large changes in attitude. The stability between coupled observers, controllers, and spacecraft dynamics is not formally established. Yuan [5] proposed a 16-stage rotation scheme for a dual-axis rotary inertial navigation system (INS) that can compensate for gyro drift errors without introducing additional system error accumulation. Wu et al. [6] proposed a Rotary Inertial Measurement Unit (RIMU) method. The accelerometer is used to measure the relationship between the components of the gravity acceleration in each axis and the angular velocity of the gyroscope. Using the dial to get relationship under different coordinate axes and to obtain the multiple equations which can be used to estimate bias. Although these methods can estimate the deviation of the gyroscope, they require a turning tool that can turn any angle around any axis. The bias of the gyroscope is obtained from experiments, but the gyro bias cannot be tracked in real time, and corrections cannot be made. Applications are limited. For example, it is difficult to apply these methods to the indoor positioning of a pedestrian. Thienel et al. [7] tracked the bias of the gyroscope in real time as the bias converged exponentially. However, this method is applied in the case of aerospace space. The motion model, which is not applicable to robots or walking navigation, has limitations. Benallegue et al. [8], used an inertial vector measurement to design an adaptive attitude tracker for a rigid body system. The angular velocity and attitude asymptotically converge to their expected values. However, their method requires controlled inputs and there is no feedback of the attitude. In addition, to estimate the gyro bias, some methods must be combined with magnetometers [9], GPS [10,11], or other external aids. However, these methods are prone to errors when unpredictable distortion of the Earth’s geomagnetic field occurs [12,13], GPS signals are not available [14], or when external auxiliary sensors cannot be installed, e.g., in an urban environment and in a building with many steel structures [15].
We propose a method that does not rely on specific sensor information. By solving the attitude angle matrix differential equation of the rigid body rotation, the recurrence relation between the quaternion of the real angle and the sensor is obtained. Therefore, when there is an arbitrary set of observations of the Euler angle input, the deviation of the gyroscope is tracked and corrected in real time. We use the long corridor information of a map to obtain true heading information. In Section 2, the method and formula derivation are introduced, and an angle observation method is provided. In Section 3, the Euler angles obtained from this angle observation method are combined with the gyro bias estimation algorithm to obtain simulation results. The results show that it is feasible for the algorithm to estimate the bias of the gyroscope.

2. Algorithm Introduction

2.1. Method

After the output of the gyroscope is processed, the angle (also called Euler angle) of the attitude of the current carrier in the geographic coordinate system is obtained and expressed as follows:
u k = f ( Ω k )
where, Ω k represents the output of the gyroscope at the current moment; u k represents the attitude angle of the object at the current moment. For Equation (1), a good attitude is obtained with a more accurate gyro output. Good positioning results and navigation trajectory are obtained with an accurate attitude angle. The output of the gyroscope inevitably contains the deviation of the gyroscope, which affects the Euler angle calculations. Over time, the errors accumulate and eventually cause the output information from the gyroscope to be completely unreliable. So the problem of how to acquire accurate gyroscope output must be solved. Likewise, accurate observations of the angle can be obtained through maps, magnetic fields or other methods. By using the long corridor information of the map, we can obtain the true heading information and inversely calculate the more accurate three-axis rotation speed:
Ω k = f 1 ( u k r )
Ω k is compared with the output of the gyroscope to obtain the gyro bias. By compensating the gyroscope output with the obtained gyro bias, accurate gyro output is obtained.

2.2. Formula Derivation

The nature of the quaternion is very favorable for expressing rotational information [16]. By deducing and analyzing the quaternion differential equation, we can obtain the relationship between the quaternion obtained from the gyroscope output and the quaternion obtained from the real data.
The quaternion differential equation is expressed as follows [17]:
q ˙ ( t ) = 1 2 ω n b b q ( t )
Equation (3) is expressed in matrix form as follows:
[ p ˙ 0 p ˙ 1 p ˙ 2 p ˙ 3 ] = 1 2 [ 0 ω n b x n ω n b y n ω n b z n ω n b x n 0 ω n b z n ω n b y n ω n b y n ω n b z n 0 ω n b x n ω n b z n ω n b y n ω n b x n 0 ] [ p 0 p 1 p 2 p 3 ]  
where ω n b x n , ω n b y n , ω n b z n are the angular velocities of the relative reference frame around each axis that are acquired directly by a three-axis gyroscope. The quaternion, q , represents the process of rotation. q = p 0 1 + p 1 i + p 2 j + p 3 k , and the imaginary unit, i , j , k , are the unit vectors of the three-dimensional space.
Using the Peano-Baker Approximation method in Equation (4) and for gyroscopes, the data output by the sensor is a discrete value; therefore, Equation (3) is expressed as follows:
q k + 1 = exp ( 1 2 [ Δ θ k ] ) q k
where Δ θ is the three-axis rotation angle obtained by integrating the angular velocities of the three axes. The resulting expression is as follows:
[ Δ θ k ] = ω n b b T s = [ 0 ω n b x n ω n b y n ω n b z n ω n b x n 0 ω n b z n ω n b y n ω n b y n ω n b z n 0 ω n b x n ω n b z n ω n b y n ω n b x n 0 ] T s
where T s is the sampling time of the gyroscope, and ω n b b is the output of the gyroscope in the carrier coordinate system. For the gyroscope output, Ω k at k, we assume that Ω k is obtained by superimposing a gyro bias, Ω b k , and a random noise, v k , on the true value, Ω k r . The bias of the gyroscope changes slowly over time; however, over a short time, the deviation of the gyroscope can be regarded as a constant. Thus, the output of the gyroscope is expressed as follows:
Ω k = Ω k r + Ω b k + v k
The symbol, r, represents real data. Then, Equation (5) is re-written as follows:
q k + 1 = exp ( [ θ k r ] 2 + [ θ b ] 2 ) q k = exp ( T s 2 w k r + T s 2 ( w b k + v k ) ) q k
because:
θ k r θ b θ b θ k r = T s 2 ( w k r w b k w b k w k r )  
For a gyroscope with a sampling rate of 100 Hz, the sampling time is T s = 10 2 s . Because the gyroscope bias is also a small value, the approximation is as follows:
[ θ k r ] [ θ b k ] [ θ b k ] [ θ k r ] 0
Therefore, according to Equation (10), and because of the nature of the matrix function, the following is introduced:
exp ( [ θ k r ] 2 ) exp ( [ θ b k ] 2 ) = exp ( [ θ b k ] 2 ) exp ( [ θ k r ] 2 )  
Then we obtain:
q k + 1 = exp ( [ θ k r ] 2 ) exp ( [ θ b k ] 2 ) q k = exp ( T s 2 w k r ) exp [ T s 2 ( w b k + v k ) ] q k
Therefore Equation (12) is expressed as follows:
q k + 1 = exp ( T s 2 w k r ) exp [ T s 2 ( w b k + v k ) ] q k = 1 k [ exp ( T s 2 w i r ) exp ( T s 2 v i ) exp ( T s 2 w b i ) ] q 1 = exp ( 1 k T s 2 w b i + 1 k T s 2 v i ) q k + 1 r
Among them, q k + 1 represents the quaternary value of the current attitude angle; q k + 1 r represents the quaternion corresponding to the current real attitude angle; exp ( 1 k T s 2 w b i ) represents the deviation of the attitude angle caused by the gyro error. Equation (13) shows that the attitude angle from the gyroscope is obtained by adding an angle change caused by the deviation of the true value of the attitude angle. Therefore, the gyro bias, w b i , is estimated by knowing the true value, q k + 1 r , of the attitude at any time.

2.3. Filter Design and Error Analysis

Because the deviation of the gyroscope changes slowly with time, when converted into the attitude angle, it is already included in the trigonometric function and becomes a nonlinear error. Using the conclusions derived above, the gyroscope bias can be expressed linearly. So we design a Kalman filter to estimate the gyroscope bias. We assume that the gyro bias is constant during a short period of time and the gyro bias is the stated quantity of our Kalman filter. The system equation is then written as follows:
X k + 1 = F X k + Q k
where X is the deviation of the three-axis gyroscope. Since the deviation is assumed to remain constant during the sampling time, F is set to a three-dimensional unit matrix. Q is the process noise, which consists mainly of the random noise of the gyroscope.
In Equation (13), we chose to use Newton’s iterative method to estimate 1 k T s 2 w b i + 1 k T s 2 v i in each iteration. Then, from the estimated 1 k 1 T s 2 w b i + 1 k 1 T s 2 v i , by subtracting them at the last moment, we obtain the estimated gyroscope deviation, w b k + v k at k, and use it as the observation, y, in our Kalman filter. In this way, we write our observation equation as follows:
y = H X k + R k
R is the observation noise, consisting mainly of the random noise of the gyroscope, the error of the Newton iteration method algorithm, and the error of the method for acquiring the attitude angle observation. We use the long corridors in the map information to acquire the observations. Because it is much smaller than the errors of the random noise and the observation error of the attitude angle, the error in the Newton iteration method can be ignored. Therefore, we analyze only the influence of the error of the attitude angle observation method in the estimation of the gyro bias. Set the roll angle, pitch angle, and heading angle deviation caused by observation error to be Δ ϕ , Δ θ , Δ ψ , respectively. Then for the actual situation:
q k = exp ( x ^ ) q k r ( ϕ + Δ ϕ , θ + Δ θ , ψ + Δ ψ )
where x ^ is 1 k T s 2 w b i + 1 k T s 2 v i , i.e., the part of the gyro bias estimation when there is an angle observation noise. For the ideal case of angle observation, i.e., observation without noise:
q k = exp ( x ) q k r ( ϕ , θ , ψ )
where x is the calculated gyroscope bias estimation section under ideal conditions; q k is the quaternion solved by the gyroscope output. This yields the following:
exp ( x ) q k r ( ϕ , θ , ψ ) = exp ( x ^ ) q k r ( ϕ + Δ ϕ , θ + Δ θ , ψ + Δ ψ )
According to the lemma of the previous section we obtain:
q k r ( ϕ , θ , ψ ) = exp ( x ^ x ) q k r ( ϕ + Δ ϕ , θ + Δ θ , ψ + Δ ψ ) = exp ( Δ x ) q k r ( ϕ + Δ ϕ , θ + Δ θ , ψ + Δ ψ )
Because q k r ( ϕ + Δ ϕ , θ + Δ θ , ψ + Δ ψ ) rotates Δ ϕ , Δ θ , Δ ψ on the basis of q k r ( ϕ , θ , ψ ) , the recurrence relation of quaternions is obtained:
q k + 1 r = [ 1 1 2 Δ θ x 1 2 Δ θ y 1 2 Δ θ z 1 2 Δ θ x 1 1 2 Δ θ z 1 2 Δ θ y 1 2 Δ θ y 1 2 Δ θ z 1 1 2 Δ θ x 1 2 Δ θ z 1 2 Δ θ y 1 2 Δ θ x 1 ] q k r
The expression of the Euler angles will be different depending on the sequence in which the coordinate axis rotates around the three axes. In this paper, expression as following:
{ Δ θ x = Δ θ Δ θ y = cos ϕ Δ ϕ + sin ϕ Δ ψ Δ θ z = cos θ sin ϕ Δ ϕ sin ϕ Δ θ cos ϕ cos θ Δ ψ
The certification process for this formula is shown in Appendix A. Then:
( e Δ x [ 1 1 2 Δ θ x 1 2 Δ θ y 1 2 Δ θ z 1 2 Δ θ x 1 1 2 Δ θ z 1 2 Δ θ y 1 2 Δ θ y 1 2 Δ θ z 1 1 2 Δ θ x 1 2 Δ θ z 1 2 Δ θ y 1 2 Δ θ x 1 ] I ) q k r ( θ ) = 0
At the same time, a Taylor expansion on e Δ x takes its linear term to be the following:
e Δ x [ 1 k T s 2 Δ w x k T s 2 Δ w y k T s 2 Δ w z k T s 2 Δ w x 1 k T s 2 Δ w z k T s 2 Δ w y k T s 2 Δ w y k T s 2 Δ w z 1 k T s 2 Δ w x k T s 2 Δ w z k T s 2 Δ w y k T s 2 Δ w x 1 ]
According to Equations (22) and (23), we obtain:
{ Δ w x = 1 k T s Δ θ x Δ w y = 1 k T s Δ θ y Δ w z = 1 k T s Δ θ z

2.4. Methods for Obtaining Observations

We choose a set of Euler angle measurements and then combine the above algorithm to estimate the gyro bias. The roll and pitch angles at this time are considered as “0”. So long as the heading angle of the foot can be obtained, we can obtain a set of Euler angles. Walking in an indoor environment, in some areas such as corridors and stair elevators, pedestrians will enter from a certain direction. The direction extracted in these specific areas can be used as a reference for the heading angle. A long straight corridor in an indoor map environment can be considered as such an area. In normal walking, pedestrians generally proceed along the direction of the corridor. Thus, long straight corridors can be used as a reference for direction correction. Assume the orientation of the corridor in the geographic coordinate system is ψ . Since there are two directions when pedestrians walk in the corridor, the observations for the heading are ψ and ψ + π . When pedestrians are walking in the corridor, we must first judge the choice of heading observations. Thus, we can use the orientation of the corridor as the real heading of a pedestrian in the corridor. The deviation of the gyroscope is estimated by solving Equation (13).
For this method of angle acquisition, we believe that only the heading angle contains errors. The roll and pitch angles are considered accurate. In this way, Equation (24) is expressed as follows:
{ Δ w x = 0 Δ w y = 0 Δ w z = 1 k T s Δ ψ
Let Δ ψ be subject to the distribution of N ( 0 , σ 2 ) . The value of σ 2 is determined by the range of values of the heading angle given by the map. Then the covariance matrix of the gyro bias due to angular observation method error is as follows:
[ 0 0 0 0 0 0 0 0 ( σ k T s ) 2 ]

3. Experiment

During the experiment, the Xsens sensor was attached to the right foot of an experimenter who walked four rounds along a corridor 39 m long and 2.4 m wide. The total duration of the experiment was 284.98 s. A preset bias was added to all the collected original gyro data of the high precision sensor. The added biases for the three axes (x, y, z) are [0.001, 0.001, 0.005] rad/s. In this experiment, as the foot moves, the sensor rotates and moves in three-dimensional space. Simultaneously, we observe the three-axis gyroscope at each zero-velocity update (ZUPT) point. The observation of the heading angle is the direction of the corridor, and at the ZUPT point, both the roll and pitch angles are zero. Pedestrian trajectory estimation is shown in Figure 1.
As seen from Figure 1, after adding noise, the corrected trajectory is significantly better than the track. In this experiment, due to the lack of the position of the true value of the foot, the results of the noise-added trajectory at the time of foot landing were compared with the results of the modified trajectory and the results of the Xsens high-precision sensor. The resulting parameter comparison is shown in Table 1.
According to the data in Table 1, the total error of the corrected path and the pre-correction comparison is reduced by 75% and the average error is reduced by 75%, indicating improvement of the trajectory drift caused by the deviation of the gyroscope. The gyro error estimate is shown in Figure 2.
As seen from Figure 2, there is a large fluctuation in the estimation of the gyroscope error in the initial period of time, but, with the passage of time (about 50 s in this experiment), the fluctuation gradually stabilizes to a certain value. The convergence time is not only caused mainly by the lack of the priori information of the gyroscope bias, but also by the orientation of the pedestrian, which is inconsistent with the map at the beginning of the experiment. After tracking the deviation of the gyroscope, the deviation of the gyroscope is estimated in real time. By the time a pedestrian turns, the person’s heading will change from around 0 to near −180°. Since the gyroscope cannot be in the state of ZUPT at all times, the heading change will affect the three axes at the same time. Thus, the deviation at the moment of turning (Figure 2) causes a downward jump. The gyro deviation of the convergence phase is averaged, and the three-axis deviation of the gyroscope is [0.00098, 0.00027, 0.0042], which is [98%, 27%, 84%] compared with the noise we added after the experiment. Over time, the gyroscope bias of the Y-axis gradually approaches the real angle and becomes more accurate.
We take the value of the bias after the deviation estimate converges to correct the trajectory with the deviation. The deviation estimate is used to calculate the trajectory comparison data obtained in the Table 2.
The comparison in Table 1 shows that, after removing the inaccuracy of the estimation due to the initial angular deviation, the overall trajectory accuracy is slightly improved. Compared with the trajectory with noise, the total error is reduced by 81%, and the average error is reduced by 81%.
For the acquired high-precision data, based on the previously added deviation, a linear bias of a slope of 5 × 10−7 is added to the z-axis of the gyroscope. Results for the gyro bias of the z-axis versus time are shown in Figure 3.
As shown, our estimated deviation also rises linearly after converging for 50 s. It conforms to the changing law of the bias we add. After 200 s, the data is averaged; then the estimated bias is 0.0113 rad/s. Assume the random noise average is zero; then the true bias is 0.0191 rad/s and the error is 0.0058 rad/s.

4. Discussion

The heading information of the long corridor of the map and ZUPT point information are used to estimate the deviation of the gyroscope. In fact, as long as it can accurately observe the angle, the algorithm can estimate the deviation of the gyroscope. The influence of angle observation error on gyroscope bias is analyzed. Regarding map information, the long corridor is just a means for obtaining the heading. Maps like escalators, long straight stairs, and even turns are used to obtain angle observations. Instead of maps, GNSS, like geomagnetism, provides angular information to estimate bias. The application is not limited to pedestrian navigation. In our experiment, based on the high-precision sensor collected by the experimenter, to correct the deviation, a fixed deviation was artificially added. In the future, the deviation of the sensor may be modeled, and the deviation of the gyroscope may be predicted.

5. Conclusions

To improve the accuracy of the navigation trajectory, we estimated the deviation of the gyroscope. Using the quaternion expression of the rotation process, we obtained the relationship between the rotation process calculated by the gyroscope output and the actual rotation process, which is caused by the deviation of the gyroscope. The true angle is obtained through the heading information of the long corridor of the map. According to the angle obtained by the gyroscope, the deviation of the gyroscope can be calculated. Experimental results show that the algorithm effectively estimates the bias of the gyroscope.

Author Contributions

Conceptualization, A.P.; Methodology, A.P. and T.T.; Software, T.T.; Validation, L.Z.; Investigation, T.T.; Data Curation, J.H.; Writing-Original Draft Preparation, T.T.; Writing-Review & Editing, T.T., A.P.; Project Administration, G.O.; Funding Acquisition, A.P.

Funding

This research was funded by National Key Research and Development Program, grant number 2018YFB0505202.

Conflicts of Interest

The authors declare no conflict of interest.

Appendix A

The expression of the Euler angles will be different depending on the sequence in which the coordinate axis rotates around the three axes. In this paper, we use the Euler angular velocity matrix has the following form [17]:
( ϕ ˙ θ ˙ ψ ˙ ) = 1 cos θ ( sin ( ϕ ) sin ( θ ) cos ( θ ) cos ( ϕ ) sin ( θ ) cos ( ϕ ) cos ( θ ) 0 sin ( ϕ ) cos ( θ ) sin ( ϕ ) 0 cos ( ϕ ) ) [ ω x ω y ω z ]
where the three-axis rotational angular velocity in the body coordinate frame, ( ω x ω y ω z ) T , is the output of the gyroscope. The Euler angular velocity is ( ϕ ˙ θ ˙ ψ ˙ ) T . Integrating time on both sides of the equation results in the following:
( ϕ θ ψ ) = 1 cos θ ( sin ( ϕ ) sin ( θ ) cos ( θ ) cos ( ϕ ) sin ( θ ) cos ( ϕ ) cos ( θ ) 0 sin ( ϕ ) cos ( θ ) sin ( ϕ ) 0 cos ( ϕ ) ) [ θ x θ y θ z ]  
From the inverse matrix, we finally obtain the following:
{ Δ θ x = Δ θ Δ θ y = cos ϕ Δ ϕ + sin ϕ Δ ψ Δ θ z = cos θ sin ϕ Δ ϕ sin ϕ Δ θ cos ϕ cos θ Δ ψ

References

  1. Zheng, Q.; Dong, L.; Lee, D.H.; Gao, Z. Active disturbance rejection control for MEMS gyroscopes. IEEE Trans. Control Syst. Technol. 2009, 17, 1432–1438. [Google Scholar] [CrossRef]
  2. Vik, B.; Shiriaev, A.; Fossen, T.I. Nonlinear observer design for integration of DGPS and INS. In New Directions in Nonlinear Observer Design; Springer: London, UK, 1999; pp. 135–159. [Google Scholar]
  3. Boskovic, J.D.; Li, S.M.; Mehra, R.K. Fault tolerant control of spacecraft in the presence of sensor bias. In Proceedings of the 2000 American Control Conference, Chicago, IL, USA, 28–30 June 2000; Voume 2, pp. 1205–1209. [Google Scholar]
  4. Boskovic, J.D.; Li, S.M.; Mehra, R.K. A globally stable scheme for spacecraft control in the presence of sensor bias. In Proceedings of the 2000 Aerospace Conference Proceedings, Big Sky, MT, USA, 25 March 2000; Volume 3, pp. 505–511. [Google Scholar]
  5. Yuan, B.; Liao, D.; Han, S. Error compensation of an optical gyro INS by multi-axis rotation. Meas. Sci. Technol. 2012, 23, 025102. [Google Scholar] [CrossRef]
  6. Wu, Z.; Sun, Z.; Zhang, W.; Chen, Q. Attitude and gyro bias estimation by the rotation of an inertial measurement unit. Meas. Sci. Technol. 2015, 26, 125102. [Google Scholar] [CrossRef] [Green Version]
  7. Thienel, J.; Sanner, R.M. A coupled nonlinear spacecraft attitude controller and observer with an unknown constant gyro bias and gyro noise. IEEE Trans. Autom. Control 2003, 48, 2011–2015. [Google Scholar] [CrossRef]
  8. Benallegue, A.; Chitour, Y.; Tayebi, A. Adaptive Attitude Tracking Control of Rigid Body Systems with Unknown Inertia and Gyro-bias. IEEE Trans. Autom. Control 2018. [CrossRef]
  9. Grip, H.F.; Fossen, T.I.; Johansen, T.A.; Saberi, A. Globally exponentially stable attitude and gyro bias estimation with application to GNSS/INS integration. Automatica 2015, 51, 158–166. [Google Scholar] [CrossRef]
  10. Yang, Y.; Farrell, J.A. Two antennas GPS-aided INS for attitude determination. IEEE Trans. Control Syst. Technol. 2003, 11, 905–918. [Google Scholar] [CrossRef]
  11. Crassidis, J.L. Sigma-point Kalman filtering for integrated GPS and inertial navigation. IEEE Trans. Aerosp. Electron. Syst. 2006, 42, 750–756. [Google Scholar] [CrossRef]
  12. De Vries, W.H.K.; Veeger, H.E.J.; Baten, C.T.M.; van der Helm, F.C.T. Magnetic distortion in motion labs, implications for validating inertial magnetic sensors. Gait Posture 2009, 29, 535–541. [Google Scholar] [CrossRef] [PubMed]
  13. Palermo, E.; Rossi, S.; Patanè, F.; Cappa, P. Experimental evaluation of indoor magnetic distortion effects on gait analysis performed with wearable inertial sensors. Physiol. Meas. 2014, 35, 399. [Google Scholar] [CrossRef] [PubMed]
  14. Chowdhary, G.; Johnson, E.N.; Magree, D.; Wu, A.; Shein, A. GPS-denied Indoor and Outdoor Monocular Vision Aided Navigation and Control of Unmanned Aircraft. J. Field Robot. 2013, 30, 415–438. [Google Scholar] [CrossRef]
  15. Afzal, M.H.; Renaudin, V.; Lachapelle, G. Use of earth’s magnetic field for mitigating gyroscope errors regardless of magnetic perturbation. Sensors 2011, 11, 11390–11414. [Google Scholar] [CrossRef] [PubMed]
  16. Titterton, D.; Weston, J.L. Strapdown Inertial Navigation Technology; The Institution of Engineering and Technology: London, UK; The American Institute of Aeronautics: Reston, VA, USA, 2004; pp. 42–43, 315–322. [Google Scholar]
  17. Diebel, J. Representing attitude: Euler angles, unit quaternions, and rotation vectors. Matrix 2006, 58, 1–35. [Google Scholar]
Figure 1. Pedestrian trajectory based on gyro bias estimation.
Figure 1. Pedestrian trajectory based on gyro bias estimation.
Sensors 18 02534 g001
Figure 2. (a) Gyroscope bias estimation based on map information; (b) Variation of covariance matrix of Kalman filter with time.
Figure 2. (a) Gyroscope bias estimation based on map information; (b) Variation of covariance matrix of Kalman filter with time.
Sensors 18 02534 g002
Figure 3. Gyroscope z-axis bias estimation based on map information.
Figure 3. Gyroscope z-axis bias estimation based on map information.
Sensors 18 02534 g003
Table 1. Comparison of gyro error estimation trajectory drift based on quaternion.
Table 1. Comparison of gyro error estimation trajectory drift based on quaternion.
Original Path (m)Noise Path (m)Corrected Path (m)
Drift Mean07.101.75
Median drift05.301.21
Total drift01746.60428.09
Positioning error2.7522.705.88
Table 2. Gyro Error Estimation Trajectory Comparison Based on Map Information.
Table 2. Gyro Error Estimation Trajectory Comparison Based on Map Information.
Original Path (m)Noise Path (m)Corrected Path (m)
Drift Mean07.101.32
Median drift05.301.00
Total drift01746.60325.34
Positioning error2.7522.704.34

Share and Cite

MDPI and ACS Style

Tan, T.; Peng, A.; Huang, J.; Zheng, L.; Ou, G. A Gyroscope Bias Estimation Algorithm Based on Map Specific Information. Sensors 2018, 18, 2534. https://doi.org/10.3390/s18082534

AMA Style

Tan T, Peng A, Huang J, Zheng L, Ou G. A Gyroscope Bias Estimation Algorithm Based on Map Specific Information. Sensors. 2018; 18(8):2534. https://doi.org/10.3390/s18082534

Chicago/Turabian Style

Tan, Tian, Ao Peng, Junjun Huang, Lingxiang Zheng, and Gang Ou. 2018. "A Gyroscope Bias Estimation Algorithm Based on Map Specific Information" Sensors 18, no. 8: 2534. https://doi.org/10.3390/s18082534

APA Style

Tan, T., Peng, A., Huang, J., Zheng, L., & Ou, G. (2018). A Gyroscope Bias Estimation Algorithm Based on Map Specific Information. Sensors, 18(8), 2534. https://doi.org/10.3390/s18082534

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