Next Article in Journal
Optimizing Data Distribution Service Discovery for Swarm Unmanned Aerial Vehicles Through Preloading and Network Awareness
Previous Article in Journal
Finite-Time Adaptive Reinforcement Learning Control for a Class of Morphing Unmanned Aircraft with Mismatched Disturbances and Coupled Uncertainties
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Real-Time Wind Estimation for Fixed-Wing UAVs

1
School of Aeronautics, Northwestern Polytechnical University, Xi’an 710072, China
2
Xi’an Research Institute of Surveying and Mapping, Xi’an 710054, China
*
Author to whom correspondence should be addressed.
Drones 2025, 9(8), 563; https://doi.org/10.3390/drones9080563
Submission received: 4 July 2025 / Revised: 3 August 2025 / Accepted: 8 August 2025 / Published: 11 August 2025

Abstract

Wind estimation plays a crucial role in atmospheric boundary layer research and aviation flight safety. Fixed-wing UAVs enable rapid and flexible detection across extensive boundary layer regions. Traditional meteorological fixed-wing UAVs require either additional wind measurement sensors or sustained turning maneuvers for wind estimation, increasing operational costs while inevitably reducing mission duration and coverage per flight. This paper proposes a real-time wind estimation method based on an Unscented Kalman Filter (UKF) without aerodynamic sensors. The approach utilizes only standard UAV avionics—GNSS, pitot tube, and Inertial Measurement Unit (IMU)—to estimate wind fields. To validate accuracy, the method was integrated into a meteorological UAV equipped with a wind vane sensor, followed by multiple flight tests. Comparison with wind vane measurements shows real-time wind speed errors below 1 m/s and wind direction errors within 20° (0.349 rad). Results demonstrate the algorithm’s effectiveness for real-time atmospheric boundary layer wind estimation using conventional fixed-wing UAVs.

1. Introduction

Accurate real-time measurement of atmospheric wind speed and direction has long been a critical focus in atmospheric boundary layer research [1,2,3,4]. It is equally vital for aviation applications, including environmental monitoring, search and rescue operations, and civil aviation safety [5,6,7]. Traditional atmospheric boundary layer studies employ balloon-borne instruments, categorized into radiosondes and tethered balloons. Radiosondes ascend with scientific payloads, transmitting real-time wind measurements from various altitudes via radio signals [8,9,10]. These non-recoverable systems incur high per-launch costs. Tethered balloons, constrained by cables, are susceptible to meteorological interference, exhibit limited maneuverability, and offer restricted spatial coverage for wind measurements. In recent years, UAVs have been widely adopted for atmospheric boundary layer sampling due to their cost-effectiveness and operational flexibility [11,12,13,14].
Wind measurement sensors commonly equipped on meteorological UAVs include multi-hole probes (MHPP) and wind vane sensors. The multi-hole pressure probe is operated by calculating the differences in static, dynamic, and hydraulic pressure of fluid flow at each hole, offering advantages such as high precision and fast response [11,15]. Current multi-hole pressure probes include 5-hole, 7-hole, and 9-hole variants; however, the probes’ limited measurement range for angle of attack (AOA) and angle of sideslip (AOS) restricts their use to some extent. In the study by Kroonenberg et al. [16], a meteorological mini-UAV equipped with a five-hole probe (FHP) was used for wind field measurement. A Kalman filter was employed to compute the UAV’s ground speed, position, and attitude; flight test results agreed with tower measurements. Li et al. [17] utilized a five-hole pressure probe to estimate vertical updrafts and, through simulation, verified that the multi-hole probe-based vertical wind speed estimation method offers higher accuracy and robustness, as well as better wind energy harvesting at lower gliding airspeeds. Based on the same principle, J. Bange et al. [18] estimated wind speed information using a five-hole probe and compared it with local meteorological mast data, showing good agreement. Commercially available multi-hole pressure probes (MHPPs) are often prohibitively expensive, sometimes exceeding the cost of the fixed-wing UAV system itself. Consequently, studies have employed rapid prototyping techniques to manufacture low-cost MHPPs [19]. However, these custom probes still require extensive calibration experiments to validate their measurement validity and accuracy prior to operational deployment.
A wind vane is an angular sensor used to measure the AOA and AOS. Combined with the airspeed measured by a pitot tube, the 3-D airspeed components can be derived; subsequently, the 3-D wind speed can be computed by combining vector triangles. A. Mohamed et al. [20] investigated the correlation between variations in airflow pitch angle and changes in wing surface pressure. Atmospheric turbulence simulations revealed a significant high correlation near the aircraft’s leading edge, indicating that optimal sensor placement on micro air vehicles (MAVs) could enable pressure-based attitude control systems. Nikola Gavrilovic et al. [21] proposed a novel system for AOA estimation based on wing pressure measurements, applicable for real-time estimation during flight and capable of further constructing the wind vector with additional equipment. Comparison with magnetic sensors in a wind vane showed that the AOA estimates provided by the pressure ports were more reliable than those given by the wind vane.
Ultrasonic wind sensors measure wind speed and direction based on the ultrasonic time-of-flight principle, typically deployed on multirotor UAVs. Ian Boisblanc [22] designed a hexacopter UAV as a wind field measurement platform, conducting comparative evaluations of various anemometry systems and ultimately selecting ultrasonic anemometers for wind field measurements. Shimura et al. [23] mounted an ultrasonic anemometer on a hexacopter UAV to measure wind profiles at 1000 m above ground level (AGL). Patrick P. Neumann [24] developed a method for estimating local wind vectors using onboard sensors to minimize payload requirements on quadrotor micro-UAVs, validating the approach through wind tunnel and field tests. Palomaki et al. [25] confirmed the validity and feasibility of UAV-mounted ultrasonic anemometers through multiple flight tests against meteorological mast reference data. Kevin A. Adkins et al. [26] detailed the construction of a UAV platform, sensor selection criteria, and optimal ultrasonic anemometer placement, while outlining the platform’s significance for meteorological research and future refinements. Wind vanes and ultrasonic sensors require careful placement during use. These sensors are highly sensitive to surrounding airflow disturbances and must avoid propeller-induced flow interference, typically requiring a minimum separation distance of 40–50 cm [23]. This configuration imposes stringent flight stability requirements while inevitably degrading the UAV’s aerodynamic characteristics and reducing flight endurance.
Wind field perception based on the dead reckoning principle primarily utilizes the UAV’s horizontal circling airspeed vector to determine its absolute motion position and perform dead reckoning for wind field computation. M. A. Shuqing et al. [27] proposed the horizontal airspeed zeroing method and the analytical wind measurement method; both methods require the UAV to fly at constant airspeed and constant angular velocity. The horizontal airspeed zeroing method necessitates the UAV completing a full circular trajectory for a single wind speed measurement, while the analytical wind measurement method requires measurements at multiple points. Mayer proposed a wind measurement method utilizing ground speed and flight path azimuth information from the autopilot’s GNSS system, where the UAV performs constant-airspeed spiral flight to measure the wind field [28,29]. Compere proposed a wind arc method that uses GNSS and heading sensors to estimate the wind vector in the Earth-fixed frame during UAV turns [30]. Wind estimation methods based on the dead reckoning principle require the UAV to perform turning maneuvers at a constant angular rate, imposing demanding flight control requirements. Under gust disturbance conditions, the accuracy of wind estimation results would be significantly compromised.
Cho et al. [31] proposed a relatively simple nonlinear Kalman filtering technique for horizontal wind estimation under the assumption of negligible vertical wind components. Rhudy [32] improved upon Cho’s work by accounting for vertical wind effects, presenting three distinct nonlinear state-space formulations for wind estimation. Results demonstrated that when AOA and AOS were available measurements in the aircraft system, simulation data from test flights most closely matched meteorological station references. Existing Kalman filter-based wind estimation techniques still require AOA and AOS inputs for accurate wind estimation, implying UAVs must carry additional airflow angle sensors.
Integrating machine learning (ML) algorithms with UAV wind measurement represents a new research direction in recent years. ML algorithms assist in noise filtering, sensor bias compensation, and wind pattern prediction [33,34]. Most ML algorithms require extensive training datasets and primarily support offline data analysis [35]. Although the Echo State Networks (ESNs) require no training, their performance is inferior to other techniques and currently cannot undergo online training experiments [36].
Multirotor UAVs facilitate observation of wind shear profiles due to operational simplicity, rapid deployment capability, and vertical/hover mobility [37]. By modeling the multirotor as a dynamic system, wind disturbances are estimated through changes in UAV position and attitude to derive wind speed/direction [24,38,39,40]. Multirotor wind estimation methods are constrained by aerodynamic and propulsion models, with parameters applicable only to specific multirotor configurations. Adapting to different multirotor types requires parameter regeneration through wind tunnel tests or calibration flight experiments.
This paper proposes a 2-D wind estimation method for fixed-wing UAVs, with comparative validation against measurements from an onboard wind vane sensor. The approach requires no additional wind measurement sensors and is directly applicable to conventional fixed-wing UAVs, significantly reducing wind sensing costs. It enables real-time wind estimation during cruise flight without specialized trajectories. Compared to existing Kalman filter-based wind estimation techniques, this method does not estimate vertical wind components but explicitly accounts for their influence on horizontal estimation. By incorporating aircraft attitude angles into the nonlinear estimation framework and refining the nonlinear state-space formulation, the observation equation’s dimensionality is enhanced. Decoupling horizontal wind estimation from vertical wind disturbances yields improved accuracy in northward and eastward wind component estimates. Results demonstrate a high level of agreement between the algorithm’s estimates and wind vane measurements in both wind speed and direction.
The paper is structured as follows: Section 2 details the novel wind estimation methodology. Section 3 describes the flight test system. Section 4 presents comparative results between the wind estimation algorithm and wind vane measurements. Conclusions are provided in Section 5.

2. Real-Time Wind Estimation

2.1. Fixed-Wing UAV Kinematic Equations

The vector relationship among wind speed, ground speed, and airspeed for a fixed-wing UAV in the inertial frame (NED coordinate system) can be expressed as:
V g r o u n d = V a i r + V w i n d
In the equation, V w i n d , V g r o u n d , and V a i r denote the wind velocity, ground velocity, and airspeed vectors, respectively. When describing aircraft motion states, the introduction of multiple coordinate systems is required to define components of relative position, velocity, acceleration, and external force vectors. Wind velocity vector computation necessitates transforming these variables into a unified coordinate frame. Here, the wind velocity is defined directly in the ground-fixed coordinate system, while the airspeed is defined in the airflow coordinate system, as illustrated in Figure 1.
The kinematic equations of the aircraft and wind estimation are most conveniently expressed in the inertial reference frame. Therefore, the airspeed must first be transformed into the body-fixed coordinate system and then into the ground-fixed coordinate system. The wind velocity, ground velocity, and airspeed can then be expressed as:
V g x V g y V g z = S θ ψ ϕ T S α β T V a 0 0 + V w x V w y V w z = V a g x V a g y V a g z + V w x V w y V w z
where V g x , V g y , and V g z denote the components of the vehicle’s ground velocity along the x , y , and z axes of the inertial coordinate system, respectively; V a g x , V a g y , and V a g z represent the components of the airspeed vector projected onto the x , y , and z axes of the inertial coordinate system, and the Direction Cosine Matrices S θ ψ ϕ and S α β are defined by Equations (3) and (4).
S θ ψ ϕ = cos θ cos ψ cos θ sin ψ sin θ sin θ cos ψ sin ϕ sin ψ cos ϕ sin θ sin ψ sin ϕ + cos ψ cos ϕ cos θ sin ϕ sin θ cos ψ cos ϕ + sin ψ sin ϕ sin θ sin ψ cos ϕ cos ψ sin ϕ cos θ cos ϕ
S α β = cos α cos β sin β sin α cos β cos α sin β cos β sin α sin β sin α 0 cos α
Within the atmospheric boundary layer, wind exhibits 3-D dynamics involving both horizontal and vertical convection. While this study focuses on 2-D horizontal wind speed/direction estimation, the method does not neglect the presence of vertical winds. As shown in Equation (2), the relationships among ground velocity, airspeed, and wind velocity are explicitly defined for all three axes. Consequently, the magnitude of vertical wind V w z does not affect the fundamental relationship among horizontal wind speed, ground velocity, and airspeed in the 2-D plane, nor does it compromise the accuracy of northward/eastward wind estimation. The relationship among horizontal wind velocity, ground velocity, and airspeed in the inertial frame can be expressed as:
V g x V g y = V a g x V a g y + V w x V w y

2.2. 2-D Horizontal Wind Field Parametric Equations

The state vector X , input vector U , and output vector Y for wind estimation in this work are defined as follows:
X = [ V w x , V w y ] T
U = θ , ψ , V p i t o t T
Y = [ V g x , V g y ] T
where θ and ψ denote the pitch and yaw Euler attitude angles, respectively, and V p i t o t represents the airspeed measured by the UAV’s onboard pitot tube. This nonlinear system takes the following form:
X k + 1 = f X k + w k
Y k = h X k , u k + ν k
where f ( ) and h ( ) denote the state transition function and observation function, respectively; w k and ν k represent process noise and measurement noise, both modeled as zero-mean Gaussian white noise. Considering the wind field exhibits minimal short-term variations, all state vector components follow a random walk model:
X k + 1 = X k + w k
From the aircraft kinematic equations Equation (5), the observation equation is derived as:
Y k = V a g x V a g y + V w x V w y + ν k
For fixed-wing UAVs with closed-loop rudder control, the AOS during flight is sufficiently small to neglect its influence ( β 0 ). Under normal cruise conditions, the aircraft’s AOA varies within single-digit ranges ( cos α 1 , sin α 0 ). Thus, the observation equation simplifies to:
Y k = V g x V g y = V p i t o t cos θ cos ψ V p i t o t cos θ sin ψ + V w x V w y + ν k

2.3. Nonlinear State Estimation

The UKF was selected for this study due to its high estimation accuracy for nonlinear problems and elimination of Jacobian matrix computations. The UKF flow chart is shown in Figure 2.
The standard UKF computes 2 n + 1 sigma points using the unscented transform, formulated as follows:
X k / k ( i ) = X ¯ k / k , i = 0 X ¯ k / k + ( n + λ ) P k / k , i = 1,2 , , n X ¯ k / k n + λ P k k , i = n + 1 , n + 2 , , 2 n
where n is the dimension of the state vector and P k / k is the covariance matrix. The weights for the 2 n + 1 sigma points are computed as follows:
ω m ( 0 ) = λ n + λ ω c ( 0 ) = λ n + λ + 1 α 2 + β ω m ( i ) = λ 2 ( n + λ ) ,   i = 1,2 , , 2 n
Propagate the sigma points X k / k ( i ) through the state equation to compute the one-step predicted sigma points, and calculate the predicted mean X ¯ k + 1 / k and covariance P k + 1 / k .
X k + 1 / k ( i ) = f ( X k / k ( i ) )
X ¯ k + 1 / k = i = 0 2 n ω ( i ) X k + 1 / k ( i )
P k + 1 / k = i = 0 2 n ω ( i ) ( X k + 1 / k ( i ) X ¯ k + 1 / k ) ( X k + 1 / k ( i ) X ¯ k + 1 / k ) T + Q
where Q denotes process noise covariances. Propagate the mean X ¯ k + 1 / k through Equation (14) to generate new 2 n + 1 sigma points X ¯ k + 1 / k ( i ) , then compute the predicted measurements by passing these points through the observation equation.
Y k + 1 / k ( i ) = h ( X ¯ k + 1 / k ( i ) , u k )
Compute the weighted mean Y k + 1 / k ( i ) and covariance Y ¯ k + 1 / k of the predicted measurements P y , then calculate the cross-covariance P x y between the state and measurement vectors.
Y ¯ k + 1 / k = i = 0 2 n ω ( i ) Y k + 1 / k ( i )
P y k y k = i = 0 2 n ω ( i ) ( Y k + 1 / k ( i ) Y ¯ k + 1 / k ) ( Y k + 1 / k ( i ) Y ¯ k + 1 / k ) T + R
P x k y k = i = 0 2 n ω ( i ) ( X k + 1 / k ( i ) Y ¯ k + 1 / k ) ( Y k + 1 / k ( i ) Y ¯ k + 1 / k ) T
where R denote measurement noise covariances. Compute the Kalman gain using the covariance P y y and cross-covariance P x y .
K k + 1 = P x k y k P y k y k 1
Finally, update the state estimate X ¯ k + 1 / k and covariance matrix P k + 1 / k .
X ¯ k + 1 / k + 1 = X ¯ k + 1 / k + K k + 1 ( Y k + 1 Y ¯ k + 1 / k )
P k + 1 / k + 1 = P k + 1 / k K k + 1 P y k y k K k + 1 T
The detailed parameters in the UKF are shown in Table 1.

3. Flight Test System

3.1. Fixed-Wing UAV Platform

This study employs the T-800 meteorological UAV developed by our laboratory as the flight platform, as shown in Figure 3. The UAV features a pusher propeller configuration powered by lithium batteries, combined with a high-wing design. This configuration provides an optimal mounting location for the onboard wind vane sensor and offers an enlarged forward payload bay. The UAV has a takeoff weight of 3.2 kg and a wingspan of 2 m. The general parameters of the T-800 are provided in Table 2.
The UAV is equipped with a CUAV V5+ autopilot module that controls all flight operations, while its integrated IMU unit dynamically outputs the aircraft’s attitude angles. Navigation is provided by an NEO 3 GNSS module, and airspeed measurements are acquired using a CUAV MS5525 (Guangzhou, China) high-precision differential pressure sensor. The detailed configuration of the sensors is shown in Table 3.

3.2. Wind Measurement System

A wind vane sensor is mounted on the leading edge of the T-800 wing to measure airspeed and aerodynamic angles, specifically the AOA and AOS in the UAV’s ambient airflow, as shown in Figure 4. The sensor comprises five integrated components vertically arranged: symmetrical carbon-fiber blades (primary flow-alignment structure), counterweight, mechanical rotating shaft, precision potentiometer, and mounting base. The operating principle exploits differential pressure dynamics: Airflow passing over the symmetrical blades generates unequal surface pressures, creating torque that rotates the shaft to align with the flow direction. The shaft and potentiometer’s sliding contact form an integral assembly, converting angular displacement into proportional voltage output. Due to the highly uniform conductive polymer within the potentiometer, the voltage-angle relationship maintains excellent linearity under standard operating conditions. The general parameters of the wind vane sensor are provided in Table 4.
The T-800 fixed-wing wind measurement system comprises two primary subsystems: the fixed-wing UAV platform and the ground control/display system, as shown in Figure 5. Both the wind vane-based wind field module and the UKF-based wind estimation module are integrated into the open-source flight controller. GNSS and IMU data are fused to compute ground velocity, while the pitot tube measures airspeed—both datasets feed into dual wind estimation modules. Critically, the wind vane’s measured AOA and AOS are exclusively input to the vane-based wind solution module.
During flight operations, the UKF wind estimation module performs real-time horizontal wind field calculations using ground speed and airspeed according to the methodology proposed in Section 2. Simultaneously, the wind vane sensor transmits aerodynamic angle data to the onboard computer at 10 Hz. Combined with real-time ground velocity (from GNSS) and pitot airspeed, horizontal wind speed and direction are computed via the vector triangle method defined in Equation (5). All data streams are recorded to the onboard microSD card.

3.3. Wind Tunnel Testing

Prior to flight testing, ground-based wind tunnel experiments were conducted to calibrate and validate the wind vane sensor’s measurement accuracy. The sensor, installed on the T-800 airframe, was positioned at the centerline of an open-jet wind tunnel. The experimental setup is shown in Figure 6.
The specific AOA values adjusted during the experimental process are provided in Table 5. These ranges comprehensively cover normal flight conditions for conventional fixed-wing UAVs. The wind tunnel was maintained at T-800′s cruise airspeed of 13 m/s. After airflow stabilization, wind vane sensor outputs were recorded. Wind tunnel results (Figure 7) show errors between sensor-measured angles and turntable reference values were below 0.2° (0.0035 rad).

4. Results and Discussion

To validate the consistency between the wind estimation algorithm and the wind vane sensor, the method proposed in Section 2 was implemented on the T-800 UAV’s onboard computer. Simultaneous horizontal wind measurements were conducted using both the algorithm and the wind vane sensor during flight tests. Four flight tests were performed with a total duration of 0.86 h.
Predefined waypoints were configured in the ground control station prior to takeoff, enabling autonomous trajectory following under the autopilot’s control. Two distinct flight altitudes were tested: 65 m AGL for the first two flights and 95 m AGL for the latter two. Each test commenced with ground takeoff, transitioned to the preset trajectory upon reaching the target altitude, and sustained circular loitering until mission completion. The flight path during the third circular loitering test is illustrated in Figure 8.
The experimental results from the second (65 m AGL) and third (95 m AGL) flights were selected for comparative analysis. Figure 9 presents the northward and eastward wind components measured by the wind vane sensor versus algorithm estimates during the second flight test. The algorithm-derived wind speeds exhibit strong temporal agreement with sensor measurements in both components, demonstrating rapid response capability to atmospheric wind fluctuations. Figure 10 further compares the north/east wind components between methodologies during the same flight, confirming high consistency in measurement trajectories. Notably, due to closely timed test windows, the measured wind speed ranges for northward/eastward components fell within identical intervals across both flights.
Figure 11 depicts real-time absolute errors between algorithm estimates and sensor measurements for northward/eastward wind speeds during both flight tests. Wind speed errors consistently remained within −0.8 to 1 m/s, with statistically indistinguishable error distributions between flights. These results validate both the measurement accuracy and operational stability of the proposed wind estimation methodology.
Figure 12 and Figure 13 present horizontal wind speed and direction measurements from the wind vane sensor versus algorithm estimates during the second and third flight tests, respectively. The proposed algorithm accurately tracks wind variation trends despite receiving no airflow angle inputs, demonstrating rapid and precise perception of wind fluctuations. Wind direction angles from both methods remain consistently near 300° (5.235 rad).
Figure 14 illustrates real-time absolute error distributions for wind speed and direction measurements between the wind vane sensor and the proposed algorithm during Flights 2 and 3. Compared to north/east component estimations, the horizontal resultant wind speed exhibits higher accuracy. While the algorithm precisely resolves the vector triangle of wind speed, ground speed, and airspeed, the absence of aerodynamic angle inputs slightly reduces the accuracy of north/east component estimates. A summary of the ME, RMSE, and CI for the wind estimate is presented later in Table 6. The RMSE of horizontal wind speed is 0.38 m/s. The RMSE of horizontal wind direction is 7° (0.1222 rad).
These results confirm the method’s considerable practical implications: Conventional fixed-wing UAVs can achieve real-time, high-accuracy 2-D wind field measurements in the atmospheric boundary layer without dedicated aerodynamic angle sensors.

5. Conclusions

This paper presents a real-time wind estimation method for fixed-wing UAVs without aerodynamic sensors. The approach utilizes only standard onboard avionics—GNSS, pitot tube, and IMU—to acquire pitot airspeed, ground velocity, and aircraft attitude during flight. The UKF enables accurate real-time estimation of wind speed and direction. This algorithm is based on the wind triangle relationship for wind estimation, which is independent of the aerodynamic parameters of the fixed wing and the parameters of the power system, and there is no need to construct a mathematical model of the aircraft. Therefore, it is not restricted by the type of fixed wing.
The approach requires no additional wind measurement sensors and is directly applicable to conventional fixed-wing UAVs, significantly reducing wind sensing costs. It enables real-time wind estimation during cruise flight without specialized trajectories. Compared to existing Kalman filter-based wind estimation techniques, this method does not estimate vertical wind components but explicitly accounts for their influence on horizontal estimation. By incorporating aircraft attitude angles into the nonlinear estimation framework and refining the nonlinear state-space formulation, the observation equation’s dimensionality is enhanced. Decoupling horizontal wind estimation from vertical wind disturbances yields improved accuracy in northward and eastward wind component estimates.
The developed method was flight-tested on the T-800 fixed-wing UAV platform, which concurrently carried a wind vane-based reference system. Pre-flight wind tunnel calibration confirmed the wind vane sensor’s accuracy with errors < 0.2° (0.0035 rad). Multiple flight experiments demonstrated strong agreement between the algorithm’s estimates and wind vane measurements in temporal variation trends. Consistent results across tests validate the algorithm’s stability, with real-time absolute wind speed errors < 1 m/s and wind direction errors < 20° (0.3490 rad). These findings confirm the method’s efficacy for real-time atmospheric boundary layer wind estimation using conventional fixed-wing UAVs.
On the other hand, this algorithm requires GNSS data input. When the GNSS signal is lost, normal wind estimation cannot be carried out, which is also the issue we need to focus on studying next.

Author Contributions

Conceptualization, Y.F. and W.A.; methodology, Y.F.; software, Y.F.; validation, Y.F.; investigation, W.A. and X.S.; resources, W.A., X.S. and B.S.; data curation, Y.F.; writing—original draft preparation, Y.F. and W.A.; writing—review and editing, Y.F., W.A., X.S. and B.S.; visualization, W.A.; supervision, W.A. and B.S.; project administration, W.A. and X.S.; funding acquisition, W.A. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Data Availability Statement

The original contributions presented in this study are included in the article. Further inquiries can be directed to the corresponding author.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Sziroczak, D.; Rohacs, D.; Rohacs, J. Review of using small UAV based meteorological measurements for road weather management. Prog. Aerosp. Sci. 2022, 134, 100859. [Google Scholar] [CrossRef]
  2. Adkins, K.A.; Becker, W.; Ayyalasomayajula, S.; Lavenstein, S.; Vlachou, K.; Miller, D.; Compere, M.; Krishnan, A.M.; Macchiarella, N. Hyper-local weather predictions with the enhanced general urban area microclimate predictions tool. Drones 2023, 7, 428. [Google Scholar] [CrossRef]
  3. Van den Kroonenberg, A.C.; Martin, S.; Beyrich, F.; Bange, J. Spatially-averaged temperature structure parameter over a heterogeneous surface measured by an unmanned aerial vehicle. Bound.-Layer Meteorol. 2012, 142, 55–77. [Google Scholar] [CrossRef]
  4. Mullen, J.; Bailey, S.C.C.; Hoagg, J.B. Filtered dynamic inversion for altitude control of fixed-wing unmanned air vehicles. Aerosp. Sci. Technol. 2016, 54, 241–252. [Google Scholar] [CrossRef]
  5. Dolfi-Bouteyre, A.; Canat, G.; Valla, M.; Augere, B.; Besson, C.; Goular, D.; Lombard, L.; Cariou, J.-P.; Durecu, A.; Fleury, D.; et al. Pulsed 1.5 μm LIDAR for Axial Aircraft Wake Vortex Detection Based on High-Brightness Large-Core Fiber Amplifier. IEEE J. Sel. Top. Quantum Electron. 2009, 15, 441–450. [Google Scholar] [CrossRef]
  6. Daud, S.M.S.M.; Yusof, M.Y.P.M.; Heo, C.C.; Khoo, L.S.; Singh, M.K.C.; Mahmood, M.S.; Nawawi, H. Applications of drone in disaster management: A scoping review. Sci. Justice 2022, 62, 30–42. [Google Scholar] [CrossRef]
  7. Tang, L.; Shao, G. Drone remote sensing for forestry research and practices. J. For. Res. 2015, 26, 791–797. [Google Scholar] [CrossRef]
  8. Day, B.M.; Rappenglück, B.; Clements, C.B.; Tucker, S.C.; Brewer, W.A. Nocturnal boundary layer characteristics and land breeze development in Houston, Texas during TexAQS II. Atmos. Environ. 2010, 44, 4014–4023. [Google Scholar] [CrossRef]
  9. Lehner, M.; Whiteman, C.D.; Hoch, S.W.; Jensen, D.; Pardyjak, E.R.; Leo, L.S.; Di Sabatino, S.; Fernando, H.J.S. A case study of the nocturnal boundary layer evolution on a slope at the foot of a desert mountain. J. Appl. Meteorol. Climatol. 2015, 54, 732–751. [Google Scholar] [CrossRef]
  10. Kalverla, P.C.; Duine, G.J.; Steeneveld, G.J.; Hedde, T. Evaluation of the Weather Research and Forecasting Model in the Durance valley complex terrain during the KASCADE Field Campaign. J. Appl. Meteorol. Climatol. 2016, 55, 861–882. [Google Scholar] [CrossRef]
  11. Anderson, K.; Gaston, K.J. Lightweight unmanned aerial vehicles will revolutionize spatial ecology. Front. Ecol. Environ. 2013, 11, 138–146. [Google Scholar] [CrossRef]
  12. Reuder, J.; Brisset, P.; Jonassen, M.; Mayer, S. The Small Unmanned Meteorological Observer SUMO: A new tool for atmospheric boundary layer research. Meteorol. Z. 2009, 18, 141. [Google Scholar] [CrossRef]
  13. Elston, J.; Argrow, B.; Stachura, M.; Weibel, D.; Lawrence, D.; Pope, D. Overview of small fixed-wing unmanned aircraft for meteorological sampling. J. Atmos. Ocean. Technol. 2015, 32, 97–115. [Google Scholar] [CrossRef]
  14. Marino, M.; Fisher, A.; Clothier, R.; Watkins, S.; Prudden, S.; Leung, C.S. An evaluation of multi-rotor unmanned aircraft as flying wind sensors. Int. J. Micro Air Veh. 2015, 7, 285–299. [Google Scholar] [CrossRef]
  15. Watkins, S.; Thompson, M.; Loxton, B.; Abdulrahim, M. On low altitude flight through the atmospheric boundary layer. Int. J. Micro Air Veh. 2010, 2, 55–68. [Google Scholar] [CrossRef]
  16. Van den Kroonenberg, A.; Martin, T.; Buschmann, M.; Bange, J.; Vörsmann, P. Measuring the wind vector using the autonomous mini aerial vehicle M 2 AV. J. Atmos. Ocean. Technol. 2008, 25, 1969–1982. [Google Scholar] [CrossRef]
  17. Chen, J.; Shi, Z.; Zhou, M.; Li, K.; Fan, M.; Zhang, K.; Dong, H. Modeling and simulation of UAV static soaring based on multi-hole probe. AIP Adv. 2021, 11, 075309. [Google Scholar] [CrossRef]
  18. Martin, S.; Bange, J.; Beyrich, F. Meteorological profiling of the lower troposphere using the research UAV“M2AV Carolo”. Atmos. Meas. Tech. 2011, 4, 705–716. [Google Scholar] [CrossRef]
  19. Prudden, S.; Fisher, A.; Mohamed, A.; Watkins, S. An anemometer for UAS-based atmospheric wind measurements. In Proceedings of the 17th Australian International Aerospace Congress: AIAC, Melbourne, Australia, 26–28 February 2017; Engineers Australia, Royal Aeronautical Society: Melbourne, Australia, 2017; pp. 303–308. [Google Scholar]
  20. Mohamed, A.; Watkins, S.; Fisher, A.; Marino, M.; Massey, K.; Clothier, R. Bioinspired wing-surface pressure sensing for attitude control of micro air vehicles. J. Aircr. 2015, 52, 827–838. [Google Scholar] [CrossRef]
  21. Nikola, G.; Bronz, M.; Moschetta, J.M.; Benard, E.; Pastor, P. Bio-inspired Wind Field Estimation-Part 1: AoA Measurements Through Surface Pressure Distribution. In Proceedings of the IMAV 2017, 9th International Micro Air Vehicle Conference and Competition, Toulouse, France, 18–21 September 2017; p. 1609301. [Google Scholar]
  22. De Boisblanc, I.; Dodbele, N.; Kussmann, L.; Mukherji, R.; Chestnut, D.; Phelps, S.; Lewin, G.C.; De Wekker, S. Designing a hexacopter for the collection of atmospheric flow data. In Proceedings of the 2014 Systems and Information Engineering Design Symposium (SIEDS), Charlottesville, VA, USA, 25 April 2014; IEEE: New York, NY, USA, 2014. [Google Scholar]
  23. Shimura, T.; Inoue, M.; Tsujimoto, H.; Sasaki, K.; Iguchi, M. Estimation of Wind Vector Profile Using a Hexarotor Unmanned Aerial Vehicle and Its Application to Meteorological Observation up to 1000 m above Surface. J. Atmos. Ocean. Technol. 2018, 35, 1621–1631. [Google Scholar] [CrossRef]
  24. Neumann, P.P.; Bartholmai, M. Real-time wind estimation on a micro unmanned aerial vehicle using its inertial measurement unit. Sens. Actuators A Phys. 2015, 235, 300–310. [Google Scholar] [CrossRef]
  25. Palomaki, R.T.; Rose, N.T.; van den Bossche, M.; Sherman, T.J.; De Wekker, S.F. Wind Estimation in the Lower Atmosphere Using Multirotor Aircraft. J. Atmos. Ocean. Technol. 2017, 34, 1183–1191. [Google Scholar] [CrossRef]
  26. Adkins, K.; Swinford, C.; Wambolt, P.; Bease, G. Development of a sensor suite for atmospheric boundary layer measurement with a small multirotor unmanned aerial system. Int. J. Aviat. Aeronaut. Aerosp. 2020, 7, 4. [Google Scholar] [CrossRef]
  27. Shuqing, M.; Hongbin, C.; Gai, W.; Yi, P.; Qiang, L. A miniature robotic plane meteorological sounding system. Adv. Atmos. Sci. 2004, 21, 890–896. [Google Scholar] [CrossRef]
  28. Reuder, J.; Brisset, P.; Jonassen, M.; Müller, M.; Mayer, S. Sumo: A small unmanned meteorological observer for atmospheric boundary layer research. In IOP Conference Series: Earth and Environmental Science; IOP Publishing: Bristol, UK, 2008; Volume 1, p. 012014. [Google Scholar]
  29. Mayer, S.; Hattenberger, G.; Brisset, P.; Jonassen, M.O.; Reuder, J. A ‘no-flow-sensor’wind estimation algorithm for unmanned aerial systems. Int. J. Micro Air Veh. 2012, 4, 15–29. [Google Scholar] [CrossRef]
  30. Compere, M.D.; Adkins, K.A.; Muthu Krishnan, A. Go with the Flow: Estimating Wind Using Uncrewed Aircraft. Drones 2023, 7, 564. [Google Scholar] [CrossRef]
  31. Cho, A.; Kim, J.; Lee, S.; Kee, C. Wind estimation and airspeed calibration using a UAV with a single-antenna GPS receiver and pitot tube. IEEE Trans. Aerosp. Electron. Syst. 2011, 47, 109–117. [Google Scholar] [CrossRef]
  32. Rhudy, M.B.; Gu, Y.; Gross, J.N.; Chao, H. Onboard wind velocity estimation comparison for unmanned aircraft systems. IEEE Trans. Aerosp. Electron. Syst. 2017, 53, 55–66. [Google Scholar] [CrossRef]
  33. Ilyas, M.; Noack, B.R.; Hu, G.; Xiong, H.; Gao, N.; Khan, A.; Yang, Y. Drone anemometry of atmospheric winds—A review. Phys. Fluids 2025, 37, 061302. [Google Scholar] [CrossRef]
  34. Zhu, S.; Zhao, T.; Zhang, H.; Chen, Y.; Yang, D.; Liu, Y.; Cao, J. UAVs’ Flight Dynamics Is All You Need for Wind Speed and Direction Measurement in Air. Drones 2025, 9, 466. [Google Scholar] [CrossRef]
  35. Soltaninezhad, M.; Monsorno, R.; Tondini, S. A Review of Methods and Challenges for Wind Measurement by Small Unmanned Aerial Vehicles. Meteorol. Appl. 2025, 32, e70065. [Google Scholar] [CrossRef]
  36. Baraka, A. Machine Learning Based Approaches to Dynamic Wind Estimation for Unmanned Aerial Vehicles. Master’s Thesis, New Mexico State University, Las Cruces, NM, USA, 2023. [Google Scholar]
  37. Meier, K.; Hann, R.; Skaloud, J.; Garreau, A. Wind estimation with multirotor UAVs. Atmosphere 2022, 13, 551. [Google Scholar] [CrossRef]
  38. Mayer, S.; Sandvik, A.; Jonassen, M.O.; Reuder, J. Atmospheric profiling with the UAS SUMO: A new perspective for the evaluation of fine-scale atmospheric models. Meteorol. Atmos. Phys. 2012, 116, 15–26. [Google Scholar] [CrossRef]
  39. Yu, H.; Liang, X.; Lyu, X. DOB-based Wind Estimation of A UAV Using Its Onboard Sensor. In Proceedings of the2024 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Abu Dhabi, United Arab Emirates, 14–18 October 2024; IEEE: New York, NY, USA, 2024; pp. 8126–8133. [Google Scholar]
  40. Bramati, M.; Schön, M.; Schulz, D.; Savvakis, V.; Wang, Y.; Bange, J.; Platis, A. A versatile calibration method for rotary-wing UAS as wind measurement systems. J. Atmos. Ocean. Technol. 2024, 41, 25–43. [Google Scholar] [CrossRef]
Figure 1. Definition of UAV airspeed, airflow angles, and attitude angles: (a) Airspeed and airflow angles; (b) Attitude angles.
Figure 1. Definition of UAV airspeed, airflow angles, and attitude angles: (a) Airspeed and airflow angles; (b) Attitude angles.
Drones 09 00563 g001
Figure 2. UKF flow chart.
Figure 2. UKF flow chart.
Drones 09 00563 g002
Figure 3. T-800 meteorological UAV.
Figure 3. T-800 meteorological UAV.
Drones 09 00563 g003
Figure 4. Wind vane sensor.
Figure 4. Wind vane sensor.
Drones 09 00563 g004
Figure 5. The system architecture of the T-800 fixed-wing wind measurement platform.
Figure 5. The system architecture of the T-800 fixed-wing wind measurement platform.
Drones 09 00563 g005
Figure 6. Wind vane sensor calibration experiment via wind tunnel testing.
Figure 6. Wind vane sensor calibration experiment via wind tunnel testing.
Drones 09 00563 g006
Figure 7. Wind vane sensor wind tunnel test error: (a) AOA; (b) AOS.
Figure 7. Wind vane sensor wind tunnel test error: (a) AOA; (b) AOS.
Drones 09 00563 g007
Figure 8. The circular loitering of flight path during the third test 3.
Figure 8. The circular loitering of flight path during the third test 3.
Drones 09 00563 g008
Figure 9. Comparison of wind vane measurements and algorithm estimates for northward and eastward wind speed during the flight test 2: (a) North wind; (b) East wind.
Figure 9. Comparison of wind vane measurements and algorithm estimates for northward and eastward wind speed during the flight test 2: (a) North wind; (b) East wind.
Drones 09 00563 g009
Figure 10. Comparison of wind vane measurements and algorithm estimates for northward and eastward wind speed during the flight test 3: (a) North wind; (b) East wind.
Figure 10. Comparison of wind vane measurements and algorithm estimates for northward and eastward wind speed during the flight test 3: (a) North wind; (b) East wind.
Drones 09 00563 g010
Figure 11. Northward and eastward wind component errors between wind vane measurements and algorithm estimates during the flight tests 2 and 3: (a) Flight test 2, (b) Flight test 3.
Figure 11. Northward and eastward wind component errors between wind vane measurements and algorithm estimates during the flight tests 2 and 3: (a) Flight test 2, (b) Flight test 3.
Drones 09 00563 g011
Figure 12. Comparison of wind vane measurements and algorithm estimates for horizontal wind speed and direction during the flight test 2: (a) Wind speed; (b) Wind direction.
Figure 12. Comparison of wind vane measurements and algorithm estimates for horizontal wind speed and direction during the flight test 2: (a) Wind speed; (b) Wind direction.
Drones 09 00563 g012
Figure 13. Comparison of wind vane measurements and algorithm estimates for horizontal wind speed and direction during the flight test 3: (a) Wind speed; (b) Wind direction.
Figure 13. Comparison of wind vane measurements and algorithm estimates for horizontal wind speed and direction during the flight test 3: (a) Wind speed; (b) Wind direction.
Drones 09 00563 g013
Figure 14. Horizontal wind speed and direction errors between wind vane measurements and algorithm estimates during the flight tests 2 and 3: (a) Wind speed error (Flight 2), (b) Wind direction error (Flight 2), (c) Wind speed error (Flight 3), (d) Wind direction error (Flight 3).
Figure 14. Horizontal wind speed and direction errors between wind vane measurements and algorithm estimates during the flight tests 2 and 3: (a) Wind speed error (Flight 2), (b) Wind direction error (Flight 2), (c) Wind speed error (Flight 3), (d) Wind direction error (Flight 3).
Drones 09 00563 g014
Table 1. UKF parameters.
Table 1. UKF parameters.
ParametersValue
Alpha 1 × 10 3
Beta2
Kappa0
Process noise covariances (Q) 0.01
Measurement noise covariances (R)32
sampling rates5 Hz
Table 2. General parameters of the T-800.
Table 2. General parameters of the T-800.
ParametersValue
Wing span2 m
Mean chord length0.180 m
Length1.300 m
Weight3.2 kg
Table 3. The sensor model of the T-800.
Table 3. The sensor model of the T-800.
ParametersValue
ProcessorSTM32F765/STM32F100
IMUICM-20689Accelerometer: ±20 mg
Gyroscope: ±18,000 deg/h
IMUBMI055Accelerometer: ±70 mg
Gyroscope: ±3600 deg/h
MagnetometerIST8310
BarometerMS5611 ×2
Airspeed meterMS55250.25%
GNSSNEO3-GNSS2 m
Data linkFM30
Electric machineTmotor2321/KV950
Table 4. General parameters of the wind vane sensor.
Table 4. General parameters of the wind vane sensor.
ParametersValue
Acquisition frequency10 Hz
Range (AOA)±28° (0.4887 rad)
Range (AOS)±32° (0.5585 rad)
Weight0.09 kg
Table 5. The turntable angles.
Table 5. The turntable angles.
AOAAOS
−5° (−0.0873 rad)−20° (−0.3490 rad)
0° (0 rad)−10° (−0.1745 rad)
5° (0.0873 rad)0° (0 rad)
10° (0.1745 rad)10° (0.1745 rad)
15° (0.2618 rad)20° (0.3490 rad)
Table 6. ME, RMSE, and CI values for different flights.
Table 6. ME, RMSE, and CI values for different flights.
Flight 2Flight 3
MERMSE95% CIMERMSE95% CI
V N (m/s)0.20280.3820[0.1974, 0.2081]0.28230.4021[0.2773, 0.2874]
V E (m/s)0.09690.4030[0.0904, 0.1034]0.13760.3606[0.1317, 0.1435]
V H (m/s)−0.00520.3688[−0.0113, 0.0009]−0.00300.3332[−0.0089, 0.0029]
Θ H (deg)3.84006.9795[3.7436, 3.9365]4.32555.5686[4.2636, 4.3874]
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Fu, Y.; An, W.; Su, X.; Song, B. Real-Time Wind Estimation for Fixed-Wing UAVs. Drones 2025, 9, 563. https://doi.org/10.3390/drones9080563

AMA Style

Fu Y, An W, Su X, Song B. Real-Time Wind Estimation for Fixed-Wing UAVs. Drones. 2025; 9(8):563. https://doi.org/10.3390/drones9080563

Chicago/Turabian Style

Fu, Yifan, Weigang An, Xingtao Su, and Bifeng Song. 2025. "Real-Time Wind Estimation for Fixed-Wing UAVs" Drones 9, no. 8: 563. https://doi.org/10.3390/drones9080563

APA Style

Fu, Y., An, W., Su, X., & Song, B. (2025). Real-Time Wind Estimation for Fixed-Wing UAVs. Drones, 9(8), 563. https://doi.org/10.3390/drones9080563

Article Metrics

Back to TopTop