Next Article in Journal
Implementation of a UAV–Hyperspectral Pushbroom Imager for Ecological Monitoring
Next Article in Special Issue
Towards a Model Based Sensor Measurement Variance Input for Extended Kalman Filter State Estimation
Previous Article in Journal
Drones for Conservation in Protected Areas: Present and Future
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Sensitivity to Time Delays in VDM-Based Navigation

Geodetic Engineering Laboratory, École Polytechnique Fédérale de Lausanne, Route Cantonale, 1015 Lausanne, Switzerland
*
Author to whom correspondence should be addressed.
Drones 2019, 3(1), 11; https://doi.org/10.3390/drones3010011
Submission received: 26 November 2018 / Revised: 21 December 2018 / Accepted: 4 January 2019 / Published: 14 January 2019
(This article belongs to the Special Issue Drones Navigation and Orientation)

Abstract

:
A recently proposed navigation methodology for aerial platforms based on the vehicle dynamic model (VDM) has shown promising results in terms of navigation autonomy. Its practical realization requires that control inputs are related to the same absolute time frame as inertial measurement unit (IMU) data and all other observations when available (e.g., global navigation satellite system (GNSS) position, barometric altitude, etc.). This study analyzes the (non-) tolerances of possible delays in control-input command with respect to navigation performance on a fixed-wing unmanned aerial vehicle (UAV). Multiple simulations using two emulated trajectories based on real flights reveal the vital importance of correct time-tagging of servo data while that of motor data turned out to be tolerable to a considerably large extent.

1. Introduction

Inertial navigation system/global navigation satellite system (INS/GNSS) integration is currently the dominant navigation system used to provide satisfactory short-term and long-term accuracy for unmanned aerial robots. Problems emerge when outage occurs in GNSS signal reception, which can happen as a result of loss of line of sight with satellites, by suffering interference caused by nearby high-power transmitters or by the electronics on board the unmanned aerial vehicle (UAV) itself, or because of spoofing or intentional jamming. In this situation, the GNSS measurements become either untrustworthy or unavailable and the navigation solution is based only on INS in a dead-reckoning fashion. Its accuracy is directly determined by the quality of the inertial measurement units (IMUs), which has consequently become considerably lower. After only a few seconds of GNSS outage, the position uncertainty for small UAVs using low-cost IMUs goes beyond practical use, in the order of hundreds of meters or more [1].
Recently, there have been some research activities aimed at mitigating the problems of navigation during GNSS outages using vehicle dynamic models (VDM) [1,2,3,4,5]. In such navigation systems, the platform dependent dynamic model of the UAV is used in navigation as opposed to the platform-independent approach in INS-based navigation. The VDM is fed by the control input to the UAV and predicts the linear and rotational accelerations. The control input can be provided by different sources, such as the autopilot or the microcontrollers commanding the servos, depending on the architecture of the platform.

1.1. Motivation

It would be unrealistic to assume that the control input data are available for the navigation at the exact time they are emitted. In the navigation filter, these data need to be time-tagged to be attributed to a specific execution time, and there is always an inherent delay between subsystems that possess input and output signals. Such delays can be caused by the computational load, buffering mechanism, and signal propagation, to name only a few. Although the source(s) of such delays is not the topic of this study, it is nevertheless considered in the form of incorrect time-tagging of the control input data that is necessary to compute the VDM-based navigation solution. The impact of such time-tagging errors on navigation performance needs therefore to be investigated to confirm the feasibility of (or requirements on) the real-time implementation. To the best of the authors’ knowledge, such investigations have never been reported. The goal of this study is to assess quantitatively the influence of imperfect time-tagging on VDM-based navigation performance, and hence understand the limitations that those errors can impose on real implementation.

1.2. Proposed Approach

In order to assess the effects of imperfect time-tagging, the control input was artificially corrupted by different time delays along an emulated UAV-trajectory. Then, the position error of autonomous navigation was compared to the case with perfect (unperturbed) time-tagging. The VDM-based navigation system in this research follows from Reference [1]. The corruptions were made in a controlled way, and multiple simulations were performed with different noise realizations and then were averaged over all of the runs to gain statistical confidence on the conclusions.
Section 2 covers the background material necessary to describe the principle of the employed VDM-based navigation technique. Section 3 presents the methodology of this study by explaining each step of the simulation process. The findings and discussion are presented in Section 4, and Section 5 presents the conclusion.

2. VDM-Based Navigation

VDM (Vehicle Dynamic Model) is a mathematical model describing the motion dynamics for any particular UAV. At its core, VDM includes an aerodynamic model of forces and moments applied to the flying UAV. Based on that, VDM provides linear and rotational accelerations of the UAV, further used in the navigation. This applies the physical constraints on the motion of the UAV in navigation, and therefore improves the accuracy and reliability. VDM requires no extra sensors with respect to conventional navigation setup. It exploits the knowledge on platform dynamics and the UAV control inputs, which are normally available from the autopilot. Such a free source of information that is not benefited from in conventional navigation systems, is being utilized in VDM-based navigation to estimate trajectory parameters with a higher quality within the already available sensor setup. While the essentials of VDM-based navigation system is presented here shortly, more details can be found in [1].

2.1. Frames Definition

Five reference frames considered in this research are: “inertial”, “Earth”, “local level”, “body”, and “wind” frames. The inertial frame ( x i , y i , z i ) is an Earth centered inertial (ECI) frame, while the Earth frame ( x e , y e , z e ) is an Earth centered Earth fixed (ECEF) frame. The local-level frame is oriented in north, east, and down directions denoted by ( x l , y l , z l ) or ( x N , x E , x D ) with respect to the tangent plane on a reference ellipsoid [6]. Definitions of body frame ( x b , y b , z b ) and wind frame ( x w , y w , z w ) can be perceived from Figure 1.
The wind frame has its first axis in the direction of airspeed V , and is defined by two angles with respect to body frame, angle of attack α , and sideslip angle β . The velocity of airflow caused by the UAV’s inertial velocity v and wind velocity w is denoted by airspeed vector V as
V = v w .
The rotation matrix C b w from body frame to wind frame is defined as a function of angle of attack α and sideslip angle β as
C b w = R 3 ( β ) R 2 ( α ) ,
where R i denotes the elementary rotation matrix around the i-th axis.

2.2. Vehicle Dynamic Model (VDM)

Contrary to References [2,3,4,5], Earth rotation and curvature are considered in this paper as in Reference [1]. Quaternions are used for attitude representation instead of Euler angles to avoid singularities. The VDM kinematics is presented in state space form, the model of which is
X n = r e l T , v e l T , q b l T , ω i b b T T ,
where r e l T = [ ϕ , λ , h ] is the platform position in geographical ellipsoidal coordinates, v e l T = [ V N , V E , V D ] is the velocity, q b l T = [ q 0 , , q 4 ] is the attitude, and ω i b b T = [ ω 1 , ω 2 , ω 3 ] the angular rate in vector or skew-symmetric Ω i b b form.
The dynamic model is expressed as [1,7]
r ˙ e l = D 1 v e l
v ˙ e l = C b l f b + g l ( Ω e l l + 2 Ω i e l ) v e l
q ˙ b l = 1 2 q b l ω l b b q
ω ˙ i b b = I b 1 M b Ω i b b ( I b ω i b b ) ,
where the skew-symmetric matrix representation of any ω p q r = ω 1 ω 2 ω 3 T vector is represented by Ω p q r as
Ω p q r = 0 ω 3 ω 2 ω 3 0 ω 1 ω 2 ω 1 0 .
The matrix D 1 in Equation (4) is defined as
D 1 = 1 R M + h 0 0 0 1 ( R P + h ) c o s ϕ 0 0 0 1 ,
where R P and R M represent the prime vertical radius of curvature and meridian radius of curvature, respectively. The rotation matrix C b l in Equation (5) is a function of the quaternion q b l as
C b l = f ( q b l ) = q 0 2 + q 1 2 q 2 2 q 3 2 2 ( q 1 q 2 q 0 q 3 ) 2 ( q 1 q 3 + q 0 q 2 ) 2 ( q 1 q 2 + q 0 q 3 ) q 0 2 q 1 2 + q 2 2 q 3 2 2 ( q 2 q 3 q 0 q 1 ) 2 ( q 1 q 3 q 0 q 2 ) 2 ( q 2 q 3 + q 0 q 1 ) q 0 2 q 1 2 q 2 2 + q 3 2 ,
and g l represents the gravity vector. The ω l b b vector in Equation (6) is calculated as
ω l b b = ω i b b C b l T ω i e l + ω e l l ,
where ω i e l and ω e l l are defined as follows:
ω i e l = ω i e c o s ϕ 0 ω i e s i n ϕ T
ω e l l = λ ˙ c o s ϕ ϕ ˙ λ ˙ s i n ϕ T .
The matrix I b in Equation (7) denotes the moments of the inertia matrix.
The presented model is the general dynamic model for any rigid body affected by external specific force f , external moment M , and Earth gravity g . For a specific type of UAV, fixed-wing for example, an aerodynamic model defines specific force vector f and the moments vector M as follows, with m denoting the mass of the UAV:
f b = 1 m ( F T 0 0 + C w b F x w F y w F z w )
M b = M x b M y b M z b .
Thrust, drag, lateral, and lift forces ( F T , F x w , F y w , and F z w , respectively) are the four components of aerodynamic forces. Roll, pitch, and yaw moments ( M x b , M y b , and M z b , respectively) are the three components of aerodynamic moments. While thrust force (along x b -axis) and all moment components are expressed in body frame, lift, lateral, and drag forces are expressed in wind frame:
F T = ρ n 2 D 4 C F T 1 + C F T 2 J + C F T 3 J 2
F x w = q ¯ S C F x 1 + C F x α α + C F x α 2 α 2 + C F x β 2 β 2
F y w = q ¯ S C F y 1 β
F z w = q ¯ S C F z 1 + C F z α α
M x b = q ¯ S b C M x a δ a + C M x β β + C M x ω ˜ x ω ˜ x + C M x ω ˜ z ω ˜ z
M y b = q ¯ S c ¯ C M y 1 + C M y e δ e + C M y ω ˜ y ω ˜ y + C M y α α
M z b = q ¯ S b C M z δ r δ r + C M z ω ˜ z ω ˜ z + C M z β β
where b, S, c ¯ , and D are geometric measures of the UAV representing wing span, wing surface, mean aerodynamic chord, and propeller diameter, respectively. Air density is denoted by ρ , while q ¯ is dynamic pressure defined as ρ V 2 / 2 , and J is defined as V / ( D π n ) with n denoting propeller speed. Dimensionless angular velocities are defined as ω ˜ x = b ω x / ( 2 V ) , ω ˜ y = c ¯ ω y / ( 2 V ) , and ω ˜ z = b ω z / ( 2 V ) . The aerodynamic coefficients for the particular UAV at hand are represented by C ’s, and deflections of aileron, elevator, and rudder are denoted by δ a , δ e , and δ r , respectively.
The required inputs for the aerodynamic model are dynamic (navigation) states, wind velocity, control inputs, and physical parameters of the UAV. As depicted schematically in Figure 1, the UAV type considered in this paper has a single propeller, as well as aileron, elevator, and rudder control surfaces. The aerodynamic model for this UAV type is borrowed from Reference [8], while adapting the physical parameters.

2.3. Navigation System

In the proposed navigation system, the VDM serves as the main process model within the filter. A standard extended Kalman filter (EKF) [9] is chosen in this paper to estimate corrections to the states ( Δ X ) and the associated covariance matrix (P). More detailed description of process models, observation models, and their linearization for proposed VDM-based navigation can be found in Reference [1].
As depicted in Figure 2, the VDM provides the navigation solution ( X n ), which gets updated as a part of the augmented state vector X (introduced in Equation (24) based on the available observations. Since IMU data are treated as observations, in case of an IMU failure, the navigation system stops using IMU data and provides the navigation solution using only the VDM and other available observations. Observations from other sensors such as the airspeed sensor, optic flow sensor, and magnetometer can also be integrated within the navigation system.
The VDM is fed with the control input ( U ) to the UAV as commanded by the autopilot and therefore is always available. Wind velocity ( X w ) is also required, which can be estimated within the navigation system, even in the absence of airspeed sensors, which is the case here [10]. The required VDM parameters ( X p ) can be pre-calibrated and used as fixed values in the navigation system or estimated in-flight/refined from them. The latter option is implemented to increase flexibility and accuracy of the proposed approach while minimizing design effort.
The augmented state vector X includes navigation states X n , VDM parameters X p , and wind velocity components X w .
X = [ X n T , X p T , X w T ] T
Mass ( m ) and moments of inertia I b are excluded from X p since they appear as scaling factors in the model, which means they are completely correlated with the already included aerodynamic coefficients [1]. Geometric measures are also excluded, because they can be determined a priori with much lower uncertainty compared to aerodynamic coefficients. If IMU data are available, their error, such as their biases, can also be included within the augmented states vector [1].

3. Methodology

The control input (U), as depicted in Figure 2, is fed to the VDM. In an ideal real-time implementation, the control input data should be read directly from the microcontroller that commands those inputs. For the platform used in this research, the actuators include two servos for the ailerons, one servo for the rudder, one servo for the elevator, and one motor to spin the propeller. The control input (U) is the 5 × 1 vector of the commands setting the defection of aileron (the two combined in a differential manner), elevator, and rudder, as well as the rotational speed of the propeller. In most systems, the control commands can only be accessed from the on-board computer that hosts the autopilot. The latter time-tags the data with its own system time. The data time-tagging operation requires its own processing time and depending on the system computational load, some delays can be expected between the time a control command is emitted t 0 e m i and the time when it is time-tagged t 0 t a g . This is illustrated in Figure 3.
In order to assess the influence of imperfections in data time-tagging on the performance of VDM-based navigation, a simulation scenario was setup. The steps of this simulation are depicted in Figure 4 and are detailed as follows:

3.1. Reference and Flight Simulation

The UAV used for this study is a custom made airplane equipped with the open-source autopilot Pixhawk [11]. Its operational weight is around 2.5 kg, depending on the payload, and nominal airspeed is around 15 m/s. The geometrical details of the platform are given in Reference [1]. The navigation sensors include a MEMS IMU called Navchip [12] on a custom board with a barometer. A geodetic grade GNSS receiver is on board, capable of working in real time kinematic (RTK) mode, although only the stand-alone solution is used in navigation. The sampling frequencies are 100 Hz for the IMU, 10 Hz for the barometer, and 1 Hz for the stand-alone GNSS position and velocity data.
To obtain a realistic stochastic model for IMU errors, an in-house identification was performed, using the novel approach of generalized method of wavelet moments (GMWM) [13]. A summary of the IMU error parameters from the GMWM analysis is provided in Table 1.
GNSS position and velocity errors are considered as Gaussian white noise with σ = 1 m and σ = 0.03 m/s, respectively, for each horizontal channel and σ = 2 m and σ = 0.04 m/s for the vertical channel. The error in barometric altitude data is also considered as a Gaussian white noise with σ = 0.5 m. This noise level is determined based on experimental data when barometer output was compared to post processed cm-level GNSS position as the reference.
Two flights were considered, reference trajectories of which are shown in Figure 5. The first flight, denoted as Flight 1 hereinafter, lasted 425 s; while the second flight, hereinafter referred to as Flight 2, lasted 272 s. Both flights were performed using the custom fixed-wing UAV introduced in Section 3.1. PPK (PPK = Post-Processed Kinematic = carrier-phase differential GNSS) GNSS solution with cm-level accuracy was used to generate way points to emulate the flights in the simulations.
Once the way points were generated from real flight data, the flights were simulated using the model described in Section 2.2, and corresponding error-free sensor data (IMU, GNSS, and barometer) were emulated, as were the control commands. Sensor errors were added to the emulated data afterwards according to the description in Table 1. As this study aims to assess the effects of time-tagging errors in the control input only, emulated sensor readings were introduced to avoid mixing the effects with additional errors.

3.2. Time-Tagging Errors

At this point, the time-tagging of control input data was corrupted by adding some stochastic delay to simulate a realistic case. The nature of such delay in real cases depends on the internal properties of the system and is not known exactly. In this study, time delays of control command d c c were modeled as the sum of a constant bias b and a positive random delay w as
d c c ( n ) = b + | w ( n ) | ,
where w N ( 0 , σ 2 ) . The impact of time-tagging on errors in VDM-based navigation was studied for different values of b and σ .
The control commands were separated into two groups: those related to motor propeller speed (rpm) and to the servos (for aileron, elevator, and rudder). The servo and motor rpm commands were assumed to be accessible at 10 Hz, which is the case on the employed UAV. The ideal time-tagging of the data was corrupted by delay d c c for each data set separately. The meaning of the emitted and tagged times is illustrated in Figure 3.
The navigation and filtering in the simulation was set to 100 Hz, but it also ran every time a new control input (with corrupted time-tagging) was available in the process. This guarantees that no additional delay was introduced by the processing scheme as a result of buffering.

3.3. VDM-Based Navigation

When the motor and servo time-tagging was corrupted for a particular fixed delay and absolute noise error level, VDM-based navigation was performed on the data. For both flights, 3 min long GNSS outage was considered before the trajectory ended. Maximum position errors were saved for each run with the same added timing error characteristics. For this research, there were 15 runs for every combination of fixed and random delays, each with a different noise realization.

4. Results and Discussion

This section analyzes the influence of time-tagging errors on VDM-based navigation for the two trajectories presented in Section 3.1.
First, VDM-based navigation with 3 min of GNSS outage without any time-tagging error was performed as the reference and presented as the solid line in Figure 5. Then, cases with different levels of delays were simulated separately for motor and servo commands. The corresponding maximum error in position at the end of 3 minute long autonomous navigation was 83 m for Flight 1 and 42 m for Flight 2. It can be observed that the autonomous VDM-based navigation solution drifted somewhat in both flights, though the resulting trajectory still qualitatively followed the reference one. INS-based navigation was not able to produce a result with nearly as competitive a result for the same level of noise in the inertial data.

4.1. Motor Data Time-Tagging Errors

The investigated motor data time-tagging errors range from 0 to 300 ms of fixed delay plus a random noise delay of standard deviation from 0 to 100 ms. The considered values are presented in Table 2.
Figure 6 depicts the average of the maximum position error for all runs. The max. error in position for all runs for the larger fixed delay considered (300 ms) are presented as a box-plot. In each box, the central mark indicates the median of all runs, and the bottom and top edges of the box indicate the 25th and 75th percentiles, respectively. The whiskers extend to the most extreme data points not considered outliers. The outliers are plotted individually using red ‘+’ symbol. The motor time-tagging errors seem not to introduce a noticeable deterioration of VDM-based navigation performance compared to the case with perfect time-tagging. A possible reason is the slow dynamic response of the UAV to the propeller speed, which creates the relatively small time-tagging errors (with respect to associated dynamic modes of the UAV) causing very little impact on navigation. Indeed, the absence of wind in the simulation and the nominal and almost constant velocity of the platform during both trajectories imply a very low dynamic in the change of propeller speed, simplifying the model. Larger errors in position are expected if those two conditions are different, i.e., wind is present or added in the simulation and the platform changes its velocity during the flight.

4.2. Servos Data Time-Tagging Errors

Considering the high sensitivity of UAV dynamic response to servo data time-tagging errors, the chosen fixed delay and random noise standard deviation were limited within a range from 0 to 20 ms as shown in Table 3. The effect of those errors on max. error in position is plotted in Figure 7.
The error growth in position is noticeable when time-tagging error of servo data increases. It is interesting to notice that the evolution of the errors with random delay follows a different trend per fixed delay. This may be due to relatively low number of runs per each (of many) combination. Despite larger delays also being tested, these are not presented as to stay with the main objective: identifying the main tendency of position error growth. A fixed delay of only 10 ms increases the max. error in position more than three times, even with no random delay. This reveals the importance of proper time-tagging of control input data for VDM-based navigation.
Figure 8 shows the VDM-based navigation solution both with an introduced fixed and random (standard deviation) delay of 10 ms in the servo data for a particular run. The maximum position error during a GNSS outage for both flights is around 300 m, i.e., about three times larger than the nominal scenario, although the trajectory dependency of dead reckoning methods makes the direct comparison between trajectories less relevant. Note that the magnitude of vertical errors are limited by the barometer measurements. In addition, as explained in Section 2.3, there is an in-flight refinement of the VDM parameters when GNSS data are available. Flight 1 lasted 152 s longer than Flight 2 and experienced more dynamic maneuvers, therefore it is reasonable to expect a finer estimation of the VDM parameters resulting in a slightly better performance in autonomous navigation.
Simulations were also performed combining time-tagging errors for both motor and servo data. However, when compared with servo errors only, the difference with the addition of time-tagging errors for the motor input was almost negligible. Therefore, these results are not presented.

5. Conclusions and Perspectives

This investigation assessed the influence of time-tagging errors in control input on VDM-based navigation of a fixed-wing UAV.
Two real flights were used to emulate sensor and control input data. The time-tagging of the latter was then corrupted by a combination of fixed (bias) and random (noise) delays and the effects analyzed via averaged simulations. Thereafter, the performance of VDM-based navigation was represented by the maximum position error after 3 min of GNSS outage. For both trajectories, time-tagging errors in the motor data were observed to have negligible influence on the maximum position error for all fixed and random delays considered. On the other hand, the impact of time-tagging errors in the servo data was indisputably higher. A rapid growth in the position error was observed even for delays as small as ten of milliseconds.
The results for both flights reveal a correlation with the trajectory characteristics, which is generally relevant for both kinematic as well as dynamic-based modeling. Therefore, maximum position error is not necessarily the most pertinent criterion to assess the performance of the VDM-based navigation solution. Nevertheless, it provides a bulk estimation for the engineering requirements on time-tagging realization in fixed-wing UAVs.
Further experiments could be run on rotary-wing UAVs. The influence of the motor time-tagging error for rotary-wings is expected to be more pronounced, as the speeds of propellers are the only control input for such platforms and directly affect both translation and rotational dynamics.

Author Contributions

Methodology, G.L., M.K. and J.S.; software, M.K. and G.L.; validation, J.S. and M.K.; investigation, G.L.; writing—original draft preparation, G.L.; writing—review and editing, M.K. and J.S.; visualization, G.L.; supervision, J.S. and M.K.; funding acquisition, J.S. and M.K.

Funding

Swiss DDPS, 8003518612

Acknowledgments

This research was supported by Swiss DDPS under contract 8003518612, support of which is greatly appreciated.

Conflicts of Interest

The authors declare no conflict of interest.

Abbreviations

The following abbreviations are used in this manuscript:
EKFExtended Kalman filter
GNSSGlobal Navigation Satellite System
IMUInertial Measurment Unit
INSInertial Navigation System
PVAPosition, Velocity and Attitude
RPMRotations Per Minute
PPKPost-Processed Kinematic
PVTPosition, Velocity, and Time
UAVUnmanned Aerial Vehicle
VDMVehicle Dynamic Model

References

  1. Khaghani, M.; Skaloud, J. Assessment of VDM-based Autonomous Navigation of a UAV under Operational Conditions. Robot. Auton. Syst. 2018, 106, 152–164. [Google Scholar]
  2. Koifman, M.; Bar-Itzhack, I.Y. Inertial navigation system aided by aircraft dynamics. IEEE Trans. Control Syst. Technol. 1999, 7, 487–493. [Google Scholar] [CrossRef]
  3. Cork, L.R. Aircraft Dynamic Navigation for Unmanned Aerial Vehicles. Ph.D. Thesis, Queensland University of Technology, Brisbane, Australia, 2014. [Google Scholar]
  4. Bryson, M.; Sukkarieh, S. UAV Localization Using Inertial Sensors and Satellite Positioning Systems. In Handbook of Unmanned Aerial Vehicles; Springer: Dordrecht, The Netherlands, 2015; pp. 433–460. [Google Scholar]
  5. Crocoll, P.; Seibold, J.; Scholz, G.; Trommer, G.F. Model-Aided Navigation for a Quadrotor Helicopter: A Novel Navigation System and First Experimental Results. Navigation 2014, 61, 253–271. [Google Scholar] [CrossRef]
  6. NIMA WGS84 Update Committee. Department of Defense. World Geodetic System 1984, Its Definition and Relationships with Local Geodetic Systems, 3rd ed.; Technical Report; National Imagery and Mapping Agency: Springfield, VA, USA, 2000.
  7. Stebler, Y. Modeling and Processing Approaches for Integrated Inertial Navigation. Ph.D. Thesis, EPFL, Lausanne, Switzerland, 2013. [Google Scholar]
  8. Ducard, G. Fault-Tolerant Flight Control and Guidance Systems: Practical Methods for Small Unmanned Aerial Vehicles; Springer: London, UK, 2009. [Google Scholar]
  9. Gelb, A. (Ed.) Applied Optimal Estimation; The MIT Press: Cambridge, MA, USA, 1988. [Google Scholar]
  10. Khaghani, M.; Skaloud, J. Evaluation of Wind Effects on UAV Autonomous Navigation Based on Vehicle Dynamic Model. In Proceedings of the 29th International Technical Meeting of The Satellite Division of the Institute of Navigation (ION GNSS+ 2016), Portland, OR, USA, 12–16 September 2016; pp. 1432–1440. [Google Scholar]
  11. Meier, L.; Tanskanen, P.; Heng, L.; Lee, G.H.; Fraundorfer, F.; Pollefeys, M. PIXHAWK: A Micro Aerial Vehicle Design for Autonomous Flight using Onboard Computer Vision. Auton. Robots 2012, 33, 21–39. [Google Scholar] [CrossRef]
  12. Intersense. Navchip. Available online: http://www.intersense.com/pages/16/246 (accessed on 10 December 2015).
  13. Guerrier, S.; Skaloud, J.; Stebler, Y.; Victoria-Feser, M.P. Wavelet-Variance-based Estimation for Composite Stochastic Processes. J. Am. Stat. Assoc. 2013, 108, 1021–1030. [Google Scholar] [PubMed]
Figure 1. Local level, body, and wind frames with airspeed V , wind velocity w , and unmanned aerial vehicle (UAV) velocity v [1].
Figure 1. Local level, body, and wind frames with airspeed V , wind velocity w , and unmanned aerial vehicle (UAV) velocity v [1].
Drones 03 00011 g001
Figure 2. Vehicle dynamic model (VDM)-based navigation filter architecture ( X ˜ k X ^ k | k 1 ).
Figure 2. Vehicle dynamic model (VDM)-based navigation filter architecture ( X ˜ k X ^ k | k 1 ).
Drones 03 00011 g002
Figure 3. Time-tagging of the emitted control commands with delays.
Figure 3. Time-tagging of the emitted control commands with delays.
Drones 03 00011 g003
Figure 4. Flowchart of simulations to assess effect of time-tagging errors.
Figure 4. Flowchart of simulations to assess effect of time-tagging errors.
Drones 03 00011 g004
Figure 5. Reference trajectory and navigation solution with perfect time-tagging.
Figure 5. Reference trajectory and navigation solution with perfect time-tagging.
Drones 03 00011 g005
Figure 6. Maximum position error averaged over all runs with motor time-tagging errors.
Figure 6. Maximum position error averaged over all runs with motor time-tagging errors.
Drones 03 00011 g006
Figure 7. Maximum position error averaged over all runs with servo time-tagging errors.
Figure 7. Maximum position error averaged over all runs with servo time-tagging errors.
Drones 03 00011 g007
Figure 8. Reference trajectory and navigation solution with sample servos time-tagging error.
Figure 8. Reference trajectory and navigation solution with sample servos time-tagging error.
Drones 03 00011 g008
Table 1. MEMS inertial measurement unit (IMU) error statistics.
Table 1. MEMS inertial measurement unit (IMU) error statistics.
SensorError TypeParameterValueUnit
Accelero-metersBias σ 8mg
White Noise σ 67 μ g/ Hz
1st order Gauss–Markov σ 0.15mg
T200s
Gyro-scopesBias σ 720 /h
White Noise σ 0.005 / s / Hz
1st order Gauss–Markov σ 31 /h
T200s
Table 2. Fixed and random delays for motor data.
Table 2. Fixed and random delays for motor data.
Fixed Delays [ms]Random Delays [ms]
00
1010
5020
10050
200100
300
Table 3. Fixed and random delays for servos data.
Table 3. Fixed and random delays for servos data.
Fixed Delays [ms]Random Delays [ms]
00
55
1010
1515
2020

Share and Cite

MDPI and ACS Style

Laupré, G.; Khaghani, M.; Skaloud, J. Sensitivity to Time Delays in VDM-Based Navigation. Drones 2019, 3, 11. https://doi.org/10.3390/drones3010011

AMA Style

Laupré G, Khaghani M, Skaloud J. Sensitivity to Time Delays in VDM-Based Navigation. Drones. 2019; 3(1):11. https://doi.org/10.3390/drones3010011

Chicago/Turabian Style

Laupré, Gabriel, Mehran Khaghani, and Jan Skaloud. 2019. "Sensitivity to Time Delays in VDM-Based Navigation" Drones 3, no. 1: 11. https://doi.org/10.3390/drones3010011

Article Metrics

Back to TopTop