Next Article in Journal
An Improved Approach for Reducing the Dimensionality of Wing Aerodynamic Optimization Considering Longitudinal Stability
Previous Article in Journal
Comparative Study of Soft In-Plane and Stiff In-Plane Tiltrotor Blade Aerodynamics in Conversion Flight, Using CFD-CSD Coupling Approach
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Flight-Data-Based High-Fidelity System Identification of DJI M600 Pro Hexacopter

Systems and Control Laboratory, Institute for Computer Science and Control (SZTAKI), HUN-REN, Kende utca 13-17, H-1111 Budapest, Hungary
*
Author to whom correspondence should be addressed.
Aerospace 2024, 11(1), 79; https://doi.org/10.3390/aerospace11010079
Submission received: 17 November 2023 / Revised: 21 December 2023 / Accepted: 1 January 2024 / Published: 15 January 2024

Abstract

:
Research and industrial application can require custom high-level controllers for industrial drones. Thus, this paper presents the high-fidelity dynamic and control model identification of the DJI M600 Pro hexacopter. This is a widely used multicopter in the research and industrial community due to its high payload capability and reliability. To support these communities, the focus of control model identification was on the exploration and implementation of DJI Onboard Software Development Kit (OSDK) functionalities, also including some unconventional special modes. Thus, the resulting model can be controlled with the same OSDK functionalities as the real drone, making control development and application time effective. First, the hardware and software structure of the additional DJI M600 onboard system are introduced. Then, the postulated dynamic and control system models are shown. Next, real flight test campaigns generating data for system identification are presented. Then, the mass and inertial properties are estimated for TB47S and TB48S battery sets and the custom Forerunner UAV payload. Dynamic system model identification includes the aerodynamic effects and considers hover, vertical, and horizontal forces together with static horizontal wind components and finally the rotational moments and dynamics. The control system components were identified following the structure of OSDK, including vertical, horizontal, and yaw loops. After identification, the model was validated and refined based on an unused flight test and software-in-the-loop simulation data. The simulation is provided by DJI and was also compared to real flight results. This comparison showed that the DJI simulation covers the dynamics of the real drone well, but it requires being connected to the drone and needs the controllers onboard to be implemented in advance, which limits applicability and increases development time. This was another motivation to introduce a standalone simulation in Matlab Simulink, which covers all the important modes of OSDK control and can be run solely in Matlab without any hardware support. The constructed model will be published for the benefit of the research and industrial community.

1. Introduction

Multirotor platforms with different payloads are widely applied in research and industrial applications. The DJI M600 Pro is a preferred platform due to its high payload capacity (5–6 kg) and redundant systems [1,2,3,4,5,6,7,8]. Most of the applications only utilize the factory capabilities but for specific tasks, custom high-level control is required [5,9,10,11,12,13]. The tuning requires the identification of system dynamics to be able to simulate system responses before field testing ([9,10]).
As the DJI M600 is a widely applied platform (see the references above) and the Forerunner UAV (see Figure 1) was a specific application which required a custom velocity controller (see [12,13]), our research team (see authors of [11]) decided to create a high-fidelity identification model of a DJI M600. The goal was to cover the whole flight envelope and also the factory control loops applied in DJI OSDK (Onboard Software Development Kit see [14]), providing the opportunity for simulation and controller development at any level (except for the lowest levels controlling: pitch and roll angular rates and thrust). Identification was based on real flight data, considering also the wind disturbances. The resulting Matlab Simulink simulation model is openly published (see the Supplementary Material) for the advantage of the research and industrial community.
System identification of multicopters is a widely researched topic [9,10,15,16,17,18,19,20,21,22,23,24,25]. From a model structure point of view, sources can be grouped as low-fidelity ([9,10,19,20,22,23,24,25]) and high-fidelity ([15,16,17,18,21]) methods, the latter considering details of aerodynamics and flight mechanics. Scheduled linear models are considered to be low fidelity, as their basic model is a linearized low-fidelity one. The applied methodologies for parameter estimation can be transfer function identification from input–output data [10,17,20], time domain parameter estimation for a fixed model structure (gray box identification) [9,18,19,21], frequency domain system identification [22,24,25] and even neural network-based system modeling [23]. The considered data sources can be wind tunnel and test bench [17,18,19,21] or real flight [9,10,22,23,24,25] data.
Closest to our goal was the article [9] identifying the dynamics of the DJI M600 hexacopter. Similarities include the consideration of low-level controllers and delays; however, there are significant differences, which are listed below.
  • The article presents parameter-dependent linearized models instead of high-fidelity nonlinear ones.
  • The article considers almost zero roll and pitch angles (near hover state), resulting in body and inertial forces close to each other and the neglect of roll and pitch rotational dynamics. This approximation limits model validity to low speeds (until 1.5–2 m/s).
On the contrary, our approach includes the following features:
  • Nonlinear dynamical and aerodynamical model with rotor inertial effects, quadratic air drag, rotor hub forces and the effect of rotor inflow on ascend and descend dynamics.
  • Coverage of the full flight envelope with maximum ± 25 roll and pitch angles, 18 m/s forward and side speed, 3–5 m/s ascend and descend speed and 8 m/s wind resistance (see [26]).
  • Modeling of the factory control loops from low to high-level, also including the identified special modes. Thus, the required control inputs of the simulation model are the same as those required to control the drone through DJI OSDK, providing an easy way to integrate and apply the simulation-tested controllers onboard.
The structure of the paper follows. Section 2 introduces the additional hardware and software structure of the DJI M600 Pro (further referenced as M600) applied for system identification. Then, Section 3 introduces the postulated dynamic and control model structure of the DJI M600 targeted to be identified in the article. Section 4 introduces the flight test campaigns and the basic analysis of flight data, which has led to the discovery of two special modes. Section 5 discusses mass and inertia estimation, while Section 6 introduces the process of dynamic system model identification. After dynamic system identification, Section 7 discusses the identification of control system parameters targeting to cover the DJI OSDK modes. Finally, Section 8 shows the results of high-fidelity model validation and refinement, and Section 9 concludes the paper.

2. Hardware and Control Software Structure

The stock DJI M600 was equipped with a custom onboard system to transform it into a Forerunner UAV (see Figure 1, Figure 2 and Figure 3). Figure 2 shows the connection of the onboard Nvidia Jetson Xavier NX computer to the autopilot of the DJI M600 through the OSDK UART port. This made it possible to control the drone with custom controllers sending OSDK commands through the UART port. Thus, the system was capable of flying special system identification maneuvers. Flight data logging for analysis and system identification was also completed through OSDK, reading and saving the specific packets at 50 Hz frequency. Flight test maneuvers were executed also through the stock ground control station UgCS ([27], see later).
The possibilities of OSDK control are summarized in Table 1 based on [14].
The high-fidelity simulation model is designed to implement every possibility except for the HORIZONTAL_ANGULAR_RATE and VERTICAL_THRUST cases, as these are low-level controls rarely applied in high-level mission controllers. Moreover, the direct actuation of such low-level controls can be dangerous. Thus, only the other modes were tested in the flight test campaigns to correctly identify OSDK functionalities.

3. High-Fidelity Simulation Model Structure

The high-fidelity simulation model was targeted to describe the 6 degrees of freedom (DoF) nonlinear system dynamics of the hexacopter including engine dynamic and aerodynamic effects, and the controller structure was based on the OSDK functionalities (see Table 1). The main structure is shown in Figure 4, while the controller details are shown in Figure 5.
Figure 4 shows that the 6 DoF dynamics were separated into attitude (rotational) and position (translational) dynamics, the former including the yaw (Section 6.4) and roll/pitch (Section 6.3), the latter including the vertical (Section 6.2) and horizontal (Section 6.1) dynamics. The References block covers the generation of an OSDK control flag (see Table 1 for the different modes) and the related X, Y, Z and yaw references.
The controller block is detailed in Figure 5 having the speeds of the six engines as output ( Ω ). In addition to the references, switching signals (TSwitch, NSwitch, ASwitch and YSwitch) were applied to the controllers determining if velocity or angle (TSwitch, NSwitch), altitude or velocity (ASwitch) and yaw angle or yaw rate (YSwitch) are tracked in the actual control (see Table 1 for OSDK control modes). The resulting engine speed is the sum of the controller incremental outputs Δ Ω and the initial speed for hovering Ω 0 . The overall engine speed is simply saturated because this did not cause any problems in the simulation, although it is well known that saturation can even cause instability [28]. The Reference Manager block obtains the references including OSDK flag and the states of the drone and generates the switching signals and the related X r e f , Y r e f , Z r e f and Y a w r e f references. Handling of the position kick mode (Section 8.3.1) and ground reference mode (Section 8.3.2) were also implemented inside this block.

3.1. Coordinate Systems and Transformations

Before detailing the model equations, the applied coordinate systems are considered as shown in Figure 6 and Figure 7. They are the north–east–down (NED) and Body systems. The former is in the local tangential plane of the globe with axes pointing to the north, east and inside the globe (down). The latter has its X-axis pointing toward the front of the drone, Y-axis pointing to the right and Z-axis pointing downward (see Figure 7). Because of the short distances flown by a hexacopter drone, the NED system can be considered as the inertial system. The rotational transformation between the NED and body system was defined with the well-known Euler angles, having roll ϕ , pitch θ and yaw ψ motions (see, e.g., [29]).
The horizontal velocities deduced from the DJI OSDK autopilot description (see [14]) were V N o , V E a north and east velocities defined in the NED system and V T , V N tangential and normal velocities defined parallel to the NE horizontal plane but aligned with body yaw orientation (body misalignment with the NE horizontal plane is visualized in Figure 6 with the velocity vectors being unaligned with the system). The transformation between them is defined in (1).
V T V N = cos ( ψ ) sin ( ψ ) sin ( ψ ) cos ( ψ ) V N o V E a
In addition to the coordinate systems, the engine layout and geometry of the hexacopter is crucial in modeling its dynamics. It is presented in Figure 8 together with engine rotational directions (L is for left, R is for right, F is for front, B is for back and S is for side).

3.2. Details of the 6DoF Dynamic Model

Figure 4 shows that the inputs to the attitude dynamics block are engine angular rates Ω = Ω L B Ω L F Ω L S Ω R B Ω R F Ω R S T , windspeed vector W E = W N W E W D T and groundspeed V E = V N o V E a V D T , while its outputs are the body angular rate ω B = p q r T and the Euler angles ( ϕ , θ , ψ ).
This block implements the hexacopter rotational dynamics assuming a diagonal inertia matrix J = J x J y J z (which is not completely true, as shown in Table 4, but it is a good approximation), the dynamics of the Euler angles and the calculation of the torques acting on the hexacopter body. The dynamic equations can be obtained from, e.g., [29].
p ˙ q ˙ r ˙ = 1 / J x 0 0 0 1 / J y 0 0 0 1 / J z ( J y J z ) q r ( J z J x ) p r ( J x J y ) p q + τ x τ y τ z
ϕ ˙ θ ˙ ψ ˙ = 1 s ϕ t g θ c ϕ t g θ 0 c ϕ c ϕ 0 s ϕ c θ c ϕ c θ p q r
Here, τ x , τ y , τ z are the torques acting on the hexacopter body and c , s , t g are shorthands for cosine, sine and tangent.
The inputs to the position dynamics block are the body angular rate ω B , Euler angles, engine angular rates Ω and windspeed vector W. Its outputs are the NED position and velocity V E . This block implements the hexacopter translational dynamics again deduced from [29].
u ˙ v ˙ w ˙ = r v q w p w r u q u p v + g B + 1 m f x f y f z
N ˙ E ˙ D ˙ = c θ c ψ s ϕ s θ c ψ c ϕ s ψ c ϕ s θ c ψ + s ϕ s ψ c θ s ψ s ϕ s θ s ψ + c ϕ c ψ c ϕ s θ s ψ s ϕ c ψ s θ s ϕ c θ c ϕ c θ T E B u v w
Here, m is the mass of the hexacopter, T E B is the body to earth rotational matrix, V B = u v w = T B E V E is the inertial velocity vector in the body system ( T B E = T E B T ), g B = T B E 0 0 g is the gravity vector in the body system, f x , f y , f z are the body forces acting on the hexacopter and N , E , D are the NED positions.
As on a multicopter, the torques are mostly caused by the rotor forces acting on the body first; the force models should be postulated and then the torque models. For a multicopter, the basic equilibrium state is hovering, and every control action is relative to this, increasing or decreasing the engine thrusts. This fact was considered in the control model structure (see Figure 5) where there is a base engine angular rate vector Ω 0 for hovering, and the controllers generate angular rate changes Δ Ω according to it.
The f z body vertical force model should include the effects of vertical air drag and engine thrust. The air drag can be represented with the second-order model K z V a z | V a z | also considering the sign dependence. Here, V a z is the vertical airspeed component (see (9)) and K z is the unknown drag coefficient. The vertical engine forces were represented applying the usual thrust coefficient-based model of propellers (see, e.g., [16,18,30]) and considering that the propeller thrust can change with the motion of the propeller, especially in ascension and descension [31]. Thrust coefficient diagrams in the article show that the coefficient depends linearly on the advance ratio, increases in descension (backward motion of propeller in the air) and decreases in ascension (forward motion of propeller in the air). Thus, the hover thrust model for one motor can be well described as:
T z i = c T 0 + K c 100 μ i ρ A R 2 Ω i 2
Here, ρ = 1.225 kg/m3 is air density at sea level according to International Standard Atmosphere (ISA), A = 0.2231 m2 is propeller area and R = 0.2665 m is propeller radius. Substituting the advance ratio μ i = V a z R Ω i results in (7). Note that here, the angular rate of one engine results from hover and control rates as: Ω i = Ω 0 i + Δ Ω T i + Δ Ω N i + Δ Ω a l t i + Δ Ω y a w i
T z i = c T 0 ρ A R 2 Ω i 2 K c 100 V a z ρ A R Ω i
Finally, summing up all the engine and air drag effects, the vertical force model is the following:
f z = c T 0 ρ A R 2 i Ω i 2 K c 100 V a z ρ A R i Ω i K z V a z | V a z | i L B , L F , L S , R B , R F , R S
V a E = V E W E V a B = T B E V a E = V a x V a y V a z
The horizontal body forces were modeled with hub force and air drag forces as:
f x = K h x 100 ρ A R V a x i Ω i K x V a x | V a x | f y = K h y 100 ρ A R V a y i Ω i K y V a y | V a y |
The applied hub force model K h x 100 ρ A R V a x i Ω i was derived with the simplification of the blade element-momentum theory models from, e.g., [15,16]. This simplified model is explicitly referenced in [21] (page 78 Remark 4.1), but here, time-varying Ω i engine speeds were considered. The time dependence of the variables is not denoted for the sake of simplicity. Note that all force models include the effect of the unknown wind disturbance W E through the airspeed terms, so the wind should also be estimated.
After postulating the force models, the torque models were constructed. In the horizontal rotational dynamic model of the rotor inertial forces, the air drag and the momentums resulting from the thrust forces of the six propellers were considered.
Considering [32], Figure 8 and the thrust model of the engines (7), the following model equations were made. Note that the air drag from the vertical airspeed V a z was assumed to have zero torque effect on the body; only the air drag from rotational motion was considered.
τ x = q J r ( Ω L B + Ω L F Ω L S Ω R B Ω R F + Ω R S ) + c T 0 ρ A R 2 l 2 ( Ω L B 2 + Ω L F 2 + 2 Ω L S 2 Ω R B 2 Ω R F 2 2 Ω R S 2 ) + K c ( V a z ) 100 V a z ρ A R l 2 ( Ω L B + Ω L F + 2 Ω L S Ω R B Ω R F 2 Ω R S ) K p p | p | τ y = p J r ( Ω L B + Ω L F Ω L S Ω R B Ω R F + Ω R S ) + c T 0 ρ A R 2 3 l 2 ( Ω L B 2 + Ω L F 2 Ω R B 2 + Ω R F 2 ) + K c ( V a z ) 100 V a z ρ A R 3 l 2 ( Ω L B + Ω L F Ω R B + Ω R F ) K q q | q |
Here, l = 0.60285 m is the physical length of the engine arms from the CG and J r = 7 × 10 4 kg·m2 is the inertia of the BLDC (brushless DC) engine rotor and propeller together obtained from [33].
For the vertical torque, the torque of propellers around the vertical (rotational) axes was derived and considered as a main effect together with the air drag from rotational speed: K r r | r | . In [31], the power coefficient of the motors is also almost linearly dependent on the advance ratio, leading to the following vertical torque model.
P i = c P ρ A R 3 Ω i 3 = M z i Ω i M z i = c P ρ A R 3 Ω i 2 c P = c P 0 + K p V a z R Ω i M z i = c P 0 ρ A R 3 Ω i 2 + K p ρ A V a z R 2 Ω i
Here, P i is the motor power, M z i is the motor vertical torque and c P is the power coefficient. Considering the rotor rotational directions from Figure 8 and the air drag, the postulated yaw dynamic model was:
τ z = c P 0 100 ρ A R 3 ( Ω L B 2 Ω L F 2 + Ω L S 2 + Ω R B 2 + Ω R F 2 Ω R S 2 ) + K p ρ A V a z R 2 ( Ω L B Ω L F + Ω L S + Ω R B + Ω R F Ω R S ) K r r | r |
Here, it is assumed that while hovering, the sum of engine speed terms is zero:
Ω L B 0 2 Ω L F 0 2 + Ω L S 0 2 + Ω R B 0 2 + Ω R F 0 2 Ω R S 0 2 = 0 Ω L B 0 Ω L F 0 + Ω L S 0 + Ω R B 0 + Ω R F 0 Ω R S 0 = 0

3.3. Details of Control Loop Models

Table 1 shows that there are three control logics (horizontal, vertical and yaw) which should be realized in four control loops (tangential, normal, altitude and yaw) as the horizontal control consists of tangential and normal components, as shown in Figure 5. The controller models were postulated based on conventional control system design knowledge including PID control and anti-windup to have a simple control structure (as presented in [29] for UAVs).
As conventional position control is not present on DJI M600 (see Section 4.1.1), only tangential and normal velocity tracking control was identified considering the following signal flow: velocity reference with saturation → velocity error → pitch/roll reference with anti-windup (AW) → pitch/roll error → engine speeds (assuming engine dynamics included in the controller). The tangential controller scheme is shown in Figure 9. The normal velocity tracking is the same with V N and ϕ signals instead of V T and θ . The Δ V signal is required to make an internal gain switching inside the PI+AW block; this will be detailed in Section 8. The velocity error to the angle reference part was postulated as a PI (proportional–integral) controller as the integral term is required to compensate wind in case of zero velocity reference. AW was required because angle references have to be saturated at ± 25 according to DJI specification [26]. Note that the d ( e l ) delay term was only inserted during model verification and refinement in Section 8.
The postulated altitude controller structure is presented in Figure 10. The assumed signal flow in the controller is: altitude reference ( h r e f ) → altitude error (with D down position) → saturated vertical speed reference (gain + saturation) → vertical speed error → engine speeds (assuming engine dynamics included in the controller). Note that the d ( e l ) delay term was only inserted during model verification and refinement in Section 8.
The assumed structure of the yaw angle controller was yaw angle error → yaw rate reference with saturation → yaw rate error → engine speeds (assuming engine dynamics included in the controller). The controller scheme is shown in Figure 11. Note that the d ( e l ) delay terms were considered both in identification and during model verification and refinement in Section 8.
After postulating the model structure, flight data collection for system identification was completed.

4. Flight Data Collection and Basic Model Analysis

Three flight test campaigns were conducted for the collection of persistently excited relevant flight data, each time improving the test procedures based on the experiences of the previous tests.
On 5 November 2021, back and forth and ascend/descend maneuvers were flown in high wind conditions, as listed below. The back and forth flights were aligned with the wind direction to have larger and smaller airspeeds (groundspeed was the same) and make it easier to distinguish the wind effect from other dynamics. Stop and turn control mode was applied to have yaw excitation in the hovering stat and thus proper data for yaw dynamic and control identification. Ascend/descend were performed together with position hold to have proper excitation of the vertical dynamics and control. The trajectories were generated with UgCS software. In all of the cases, the wind direction was approximately estimated from direction measurement with a flag. From now on, this test day is referenced as F T 1 (Flight Test 1).
  • F T 1 / 1 Fly against wind and with wind between two waypoints about 100 m away from each other with groundspeed limited to 5 m/s.
  • F T 1 / 2 Fly against wind and with wind between two waypoints about 100 m away from each other with groundspeed limited to 10 m/s.
  • F T 1 / 3 Fly against wind and with wind between two waypoints about 180 m away from each other with groundspeed limited to 14 m/s.
  • F T 1 / 4 Hold position and make about 60 m ascend and descend maneuvers limiting vertical speed to ± 3 m/s.
The 180 m long back and forth flight trajectory is shown in Figure 12.
Based on the experiences of the previous flight campaign, new flight tests were performed on 14 April 2022 applying the stop-and-turn mode of the autopilot to fly between given waypoints defined through the UgCS software as follows (called F T 2 ). The change was to fly triangle patterns to have wind disturbance acting from multiple directions to excite the cross-dynamics of the hexacopter. Otherwise, again, the vertical dynamics (ascend/descend) and the yaw dynamics were excited to identify all dynamics and OSDK logic (see Table 1) possible.
  • F T 2 / 1 Hold position and make about 60 m ascend and descend maneuvers limiting vertical speed to ± 3 m/s.
  • F T 2 / 2 Fly a triangular pattern back and forth with 100 m side length and groundspeed limited to 5 m/s.
  • F T 2 / 3 Fly a triangular pattern back and forth with 100 m side length and groundspeed limited to 10 m/s.
  • F T 2 / 4 Fly a triangular pattern back and forth with 180 m side length and groundspeed limited to 14 m/s.
Both the 100 m and 180 m side triangle trajectories are shown in Figure 13.
Finally, a third flight test campaign was flown on 12th August 2022 as F T 3 to collect data from the basic OSDK operational modes listed in Table 1 (except for HORIZONTAL_ANGULAR_RATE and VERTICAL_THRUST cases as stated before). All of the maneuvers were tailored to utilize and excite one specific mode of the OSDK logic. In these flights, the onboard system commanded the drone through DJI OSDK (see [14]) with the proper mode switching flag and references. DJI provides a simulator for DJI M600 through DJI Assistant 2, and before flight testing, the designed special maneuvers were verified in this simulator. During this verification, it turned out that for a step position reference command, the drone flies away (instead of moving with the given distance), which is why in the flight testing, ’position kick’ commands were applied. For details of the specialties of position mode, see Section 4.1.1.
  • F 3 / 1 Kick command in X and Y position (see the related special mode in Section 4.1.1).
  • F 3 / 2 Normal V N and tangential V T velocity doublet tracking with 3 , 5 , 10 m/s amplitudes.
  • F 3 / 3 Vertical (down V D ) velocity doublet tracking with 3 , 5 m/s amplitudes.
  • F 3 / 4 Yaw angle ψ doublet tracking with 45 , 90 amplitudes.
  • F 3 / 5 Roll ϕ and pitch θ doublet tracking with 10 amplitude.
Normal and tangential velocity refer to the forward and side ground relative velocities in a body system (see Figure 6). Data from this last flight test campaign were utilized in the identification of special behaviors of the DJI controller, the verification of the DJI simulator of M600 in DJI Assistant 2 and the refinement and final validation of the M600 simulation model.

4.1. Discovered Special Cases

Pre-analysis of control actions in the DJI simulator before flight testing showed two special cases where unexpected behavior was experienced. Unexpected is considered from a control engineering point of view. These are the horizontal position and angle-tracking modes. These special behaviors were underlined by the flight test experiences, and this section compares the simulation and flight test results of these modes.

4.1.1. Horizontal Position Reference Tracking

A step position reference did not result in the change of position with the given distance as assumed (e.g., 10 m move to the north); rather, the drone had continuous motion with constant velocity until stopping the controller. Considering the fact that the step change of any other reference caused the tracking of that reference, this was surprising (see, e.g., Figure 16), but such behavior is also discussed in the DJI description [34]. So, in horizontal position mode, the DJI M600 did not track the given position signal; rather, it moved away (this is underlined by the position response to a position kick maneuver in Figure 14).
Consequently, position kick commands were sent to the system observing the position, velocity and angular responses both in DJI simulation and real flight, as presented in Figure 14 and Figure 15. The figures show that for a 5 m (side) position kick, there was about 2–2.5 m displacement of the drone with a speed up and slow down maneuver.

4.1.2. Horizontal Angle Reference Tracking

Another specialty is the handling of angle references, as a step up and back to zero angle reference caused different behavior at the changes. The step to nonzero value caused good tracking of the nonzero signal, but upon jumping to the zero value, a braking mode was activated, which caused high overshoot of the angle because it started to track a zero velocity reference with high angle values stopping the vehicle as fast as possible. So, the zero angle reference is rather implemented as a zero velocity one, stopping the vehicle (see Figure 16 and Figure 17 presenting both DJI simulation and real flight behavior).

4.2. Verification of DJI Simulator

The F T 3 flight test maneuvers, constructed to analyze the behavior of factory OSDK control loops, were also utilized to compare flight data and DJI Simulator (referred to as software-in-the-loop (SIL) later) performance and thus verify the factory simulator of DJI M600. Details of this verification are presented in [35]. The conclusion was that the DJI simulator is appropriate for OSDK-based control development and testing. However, there are certain drawbacks of this simulation, like the need to connect the drone to the simulation computer and the need to implement the control methods onboard the drone before evaluation. The high-fidelity Matlab Simulink simulator targeted in this work makes development and testing much easier, removing the needs to connect the physical drone and to implement the control code on the onboard computer before the first test runs. This speeds up control development and application, as only the simulation-tested and -verified controllers should be implemented and built for DJI simulator and flight testing.
The first step of high-fidelity system identification was the estimation of mass and inertial data, which is presented in the next section.

5. Estimation of Mass and Inertial Data

It is relatively easy to measure the mass of a drone, but the inertial data estimation is more complicated. One possible method is to measure it swinging the drone as a pendulum [19]; another possibility is to measure the size and mass of the parts and create a 3D model with an appropriate software computing the inertias by the software itself. As equipment for pendulum tests was not available and it was relatively easy to disassemble the drone, the latter method was chosen.
The complete disassembly of the drone was not necessary; only the mass of the main parts was measured, and their dimensions were approximated. The Onshape free online 3D modeling software [36] can determine inertia from a given 3D model, so that was used for the calculation. The approximate 3D model of the stock M600 without payload is visible in Figure 18 in flight configuration with retracted landing gears.
Figure 18 shows that the drone was decomposed into six main types of parts. The description of these parts with the measured weights is summarized in Table 2. Measurement of the folding arms and motors required the removal and disassembly of one arm. These data were then used to approximate the weight of the drone body. Measuring the battery and landing gear elements was considerably easier, since they are originally removable parts.
The drone can be equipped with two types of batteries. The two options are TB47S and TB48S; the latter has larger capacity. Hence, in Table 2, both weights are stated (the larger weight belongs to TB48S). Therefore, two masses and two inertia matrices can be calculated even for the stock M600.
Figure 19 and Figure 20 show the 3D model of the M600 with the forerunner payload attached (for payload details, see Figure 2 and Figure 3). The payload components are a bit more detailed than the M600 itself, but some lightweight elements, like the carbon-fiber parts of the gimbal, were omitted from the model, as the two electric motors dominate the gimbal weight and inertia. There are blank spaces visible in both 3D models, which are of course not present in real life. The mass of these elements was neglected or incorporated into the other elements. But since inertia calculations depend on the position of the individual elements, each part has to be placed in the exact position where they actually are.
The payload elements and their data are listed in Table 3. The basic elements of the stock drone are not repeated, but they were included in the inertia calculations of the payload version as well.
Finally, the results of the mass and inertia calculations carried out by Onshape in all configurations are presented in Table 4. Note that off-diagonal values appeared in the inertia matrix because of the payload, but they are negligible compared to the diagonal values. This underlines that the diagonal inertia matrix was a valid assumption in Section 3.

6. Dynamic System Model Identification

Before starting the identification, the maximum motor speed (equal to propeller speed in case of direct drive BLDC motors) was estimated based on the figures in [33] (page 9) and real flight data. It was set to Ω m a x = 456.45 rad/s.
First the force and then the torque model parameters were identified. As the vertical force depends on the airspeed, and thus the wind disturbance first, the horizontal force model parameters were identified including the north and east horizontal wind components and assuming W D = 0 as the deterministic wind disturbance is dominantly horizontal. It was also assumed that the strength and direction of horizontal wind disturbance was constant during each flight test. Considering the 15–20 min maximum flight time, this can be approximately true.

6.1. Horizontal Force Model Identification

In case of the FT1 flight campaign, there was high wind but no crosswind excitation of the drone (flight against or with wind), while in case of FT2, there was crosswind excitation but low wind. Considering that in the postulated force model (10) both terms depend on the airspeed in low wind, it is hard to distinguish them, while in high wind, the air drag becomes dominant (considering 6 ρ A R = 0.437 , Ω m a x / 100 = 4.56 and so 6 ρ A R Ω m a x / 100 = 1.992 ). Thus, in the high wind condition of FT1, the forward air drag parameter can be determined well, and so the cross-value should be derived based on engineering assumptions, while with FT2 data, the hub force coefficients can be determined if the air drag values are known and fixed. A repeated FT2 flight in high wind could be a good solution, but it is hard to organize all the logistics of a test flight, and it is not guaranteed that an attempt in case of high wind forecast will be successful (too high wind cancels all the flight tests). That is why the collected data were utilized in the best way to obtain realistic parameters.
In the FT1 flight test campaign, back-and-forth flights were made, meaning that the horizontal wind components can be aligned with the body system to make parameter identification easier. Flight directions were ψ f w d = 38 and ψ b c k w d = 142 and considering positive tangential and normal wind velocities W T , W N for the former (can be obtained from NE wind analogously to (1)) results in W T , W N velocities for the latter doing a 180 rotation. For the positive W T , W N values and considering V T , V N , V D body aligned drone speeds, the horizontal airspeed components result were:
V a x = V T cos ( θ ) V D sin ( θ ) W T cos ( θ ) V a y = V T sin ( ϕ ) sin ( θ ) + V N cos ( ϕ ) + V D sin ( ϕ ) cos ( θ ) W T sin ( ϕ ) sin ( θ ) W N cos ( ϕ )
From the translational dynamics (4), the horizontal force Equation (10) can be related to the measured body acceleration ( a x , a y ) of the vehicle as:
m · a x = K h x 100 ρ A R V a x i Ω i K x V a x | V a x | m · a y = K h y 100 ρ A R V a y i Ω i K y V a y | V a y |
From (16), the unknowns are K h x , K h y , K x , K y , W T , and W N , while the other variables are measured by the on-board system of the M600. For the estimation of parameters, two data sets were selected (FT1/1 and FT1/2), each set including hover, climb, against (FAW = forward against wind) and with (FWW = forward with wind) wind (both 5 m/s and 10 m/s ground speed) maneuvers for persistent excitation of the horizontal forces. The limits of air drag coefficients K x , K y were determined from the maximum wind tolerance 8 m/s and maximum bank angle 25 of the M600 considering maximum wind hovering flight (see technical specifications [26]):
m · g sin ( 25 / 180 π ) = K m a x 8 2 K m a x = 0.65
Note that in FAW flight, the air velocity can be higher and so the K x limit is lower: that is why this is a realistic upper limit. The limits for K h x , K h y were assumed to be 3 and the tangential and normal wind limits were assumed to be 10 m/s (a bit above the maximum 8 m/s to allow free motion of the parameters for convergence). All of the parameter minimums were 0 as the parameters cannot change signs (invalid model). As (16) is nonlinear in the winds, the Matlab nonlinear least-squares solver lsqcurvefit was applied considering flight data Sets FT1/1 and FT1/2. Having all six parameters free, the results are as summarized in Table 5.
Table 5 shows that the longitudinal parameters K h x , K x , W T are consistent between the two sets, while the lateral parameters K h y , K y , W N are rather inconsistent, including a saturation of W N at the maximum unrealistic 10 m/s upper limit. This underlines the statement that the cross-direction was not persistently excited.
However, as in the FT2 campaign, the air drag was not dominant, an approximation of K y was obtained considering the geometric parameters of the M600. As the air drag is linearly proportional to the front area of the vehicle, which from the Y direction is 3 / 2 times smaller than from the X (see again Figure 8) K ˜ y 0.866 K x was applied (see Table 5).
After determining K x and K y from FT1, they were fixed and FT2 flight data (without air drag dominance due to the low wind) were utilized to obtain the hub force coefficients K h x , K h y . To cover a large range of maneuvers and thus provide persistent excitation, one complete 5 m/s speed triangle was combined with one 10 m/s triangle flown in the reverse direction (one CW and one CCW), forming four different data sets. The model structure was the same as postulated in Equations (15) and (16) completed with (17), showing the transformation from NE to TN wind components as from the triangle flights. Only the NE components can be determined.
W T = W N cos ( ψ ) + W E sin ( ψ ) W N = W N sin ( ψ ) + W E cos ( ψ )
Finally, making K x , K y fix from the previous model gave satisfactory results with only a few outliers as Table 6 shows. Outliers were defined as values more than 30 % larger or smaller than the others. They are caused by turbulence and windgust disturbances in the real flight data.
In the next step, the resulting average K h x , K h y values were fixed, and the other parameters were fit to check model’s validity ( K x , K y should result the same as the fixed values from FT1). The results (again with outliers) are shown in Table 7.
The wind values are close to the previous results (also the outliers), while K x and K y are far from the previous ranges. As there is no other data set to be applied, the average results from F T 1 (Table 5) and F T 2 (Table 7) were finally considered as K x = 0.0775 , K y = 0.0714 . Fixing them and ensuring a fit for the hub force and wind disturbances gave the final model values in Table 8.
Again, the outliers are at the same places. The average K h x , K h y values are smaller than in the first round (see Table 6) but larger than from the previous flight campaign, giving a model balanced between the two cases. The absolute value of average wind result was 2.03 m/s, while its direction was 36.55 (southeast). The Windguru weather and wind forecast (see [37]) for 14 April 2022 is presented in Figure 21 (on-site wind measurements were not calculated due to the lack of equipment). The system identification flights were between 11 and 11:30, and the predicted wind for that time range is 2–3 m/s southeast. The system identification well covers the southeast (a bit more south) direction and is close to the 2–3 m/s with a 2 m/s estimate. So, the estimated model values can be accepted as realistic.
Fixing the hub force and air drag model parameters at the new values makes it possible to re-identify the wind disturbances in the two flights in F T 1 . The results are shown in Table 9. The table shows that there is only one outlier; the other results are close, so the averages can be easily calculated. The results show that the wind disturbances were lower than previously estimated, which is realistic, as the previous estimates were too close to the maximum (8 m/s) wind tolerance of the M600, while there was no problem even with 14 m/s flight speeds. Unfortunately, there is no saved Windguru forecast for the day of that test.
Evaluation of the final 3D simulation model showed that the maximum 18 m/s flight speed of M600 (in still air, see [26]) could not be achieved due to the too high air drag coefficients. So, fine tuning was performed, decreasing the K x air drag in forward flight until reaching 18 m/s. Finally, K x = 0.072 was a proper value and so K y was decreased with the same ratio to K y = 0.0663 . Fixing K x , K y and re-identifying the other parameters for the second flight test campaign ( F T 2 ) gave the values listed in Table 10. Here, the spread of the values is lower than in the previous case (Table 8), showing that the refinement moved the parameters into the proper direction. Testing again for the reaching of 18 m/s showed that K h x and K h y should be slightly decreased to K h x = 0.94 and K h y = 0.7641 (the same ratio as for K h x ). The wind estimates were not updated, as they were close to the previous ones.
Figure 22, Figure 23, Figure 24 and Figure 25 show the final model outputs compared to the flight measured horizontal forces for F T 1 (hover, climb, FAW 5 m/s, FWW 5 m/s, FAW 10 m/s, FWW 10 m/s) and F T 2 (5 m/s and 10 m/s triangle flights). Note that system identification was completed considering the specific sections where clear vertical or horizontal movements arise without vertical rotation. These sections were cut out from the continuous data. That is why there are gaps between the data sections in the figures: because the non-specific parts are not compared and thus not plotted.
The figures show that the measured accelerations and thus the dynamic forces are very noisy, and there can be large differences between the measured and the model forces. This is the reason why performance measures (such as (23)) were not applied, as they gave unacceptably large results for any model. However, the model well follows the range and dynamic changes of the measurements, so in light of the high uncertainty in the parameter identification, the model performance is acceptable.

6.2. Vertical Force Model Identification

Considering the vertical force model (8) first, the hover thrust coefficient c T 0 and the hover engine speed Ω 0 were identified considering flight data sections with V a 0 . In hover, the vertical gravitational force should be compensated by the engines:
m g cos θ cos ϕ = c T 0 ρ A R 2 i Ω i 2
In the identification, i Ω i 2 is substituted with 6 Ω 2 ¯ , which is the average squared engine angular rate.
Ω 2 ¯ = Ω L B 2 + Ω L F 2 + Ω L S 2 + Ω R B 2 + Ω R F 2 + Ω R S 2 6
Hovering flight test sections were considered from F T 1 and F T 2 flights with TB48S batteries and so m = 10.04 kg mass and from F T 2 flight with TB47S batteries and so m = 9.53 kg. c T 0 was calculated as the mean of the ratio
c T 0 = m g cos θ cos ϕ 6 ρ A R 2 Ω 2 ¯
for every flight section. Also, Ω 0 = Ω 2 ¯ ¯ was calculated as the average (of the averages) hover engine speed. The results are summarized in Table 11 and Table 12 for m = 9.53 kg and m = 10.04 kg, respectively.
The tables show that the results are similar for the two different masses giving only slightly lower hover engine speed for the lower mass. As the final goal in the Forerunner project was flight with payload finally, the data for the larger mass (Table 12) were averaged to obtain the setpoint:
c T 0 = 0.0105 Ω 0 = 283.032 rad / s
Figure 26 and Figure 27 show the engine speed and the vertical forces in the FT1/3 hover case. Figure 26 shows that the engine speeds are not all equal, as there is a need for roll and pitch to compensate for wind disturbance (position hold). However, their values are almost constant. Figure 27 shows the body vertical force from gravity and from the hover engine model, giving values very close to each other (errors between 0.02 and 0.1 N).
After identifying the hover thrust coefficient and hover engine speed, the full thrust model was targeted considering m a z = f z , (8) and that c T 0 is known.
Trying to fit the model ( K c , K z ) to ascend/descend/FAW flight data showed that a single vertical airspeed-dependent gain K c ( V a z ) is sufficient to cover it; K z was not required. This was because (according to [31]) in ascending flight, the rotor thrust coefficient decreases while in descending flight, it increases, and this is a similar effect to the air drag (down in ascension and up in descension). As both effects are airspeed dependent, they cannot be distinguished. So, the force model in (8) was modified by deleting the air drag term and including an airspeed-dependent K c ( V a z ) gain.
f z = c T 0 6 ρ A R 2 Ω 2 ¯ K c ( V a z ) 100 V a z 6 ρ A R Ω ¯
Again, the sums of engine angular rates were replaced by the average values for parameter identification, resulting in:
Ω ¯ = Ω L B + Ω L F + Ω L S + Ω R B + Ω R F + Ω R S 6
In the first flight campaign ( F T 1 ), the persistently excited data sections (regarding V a z ) were ascend/descend, FAW 10 m/s and FAW 14 m/s. As the V a z airspeed values depend on the wind disturbances, their estimates from Table 9 were applied in the calculation. Separate K c constant coefficients were determined through linear least-squares fit for the different V a z ranges. The estimated coefficients, together with the dominant V a z values from the first flight campaign, are shown in Table 13. Estimates from the second flight campaign are presented in Table 14 calculated with wind values from Table 10. The second flight campaign includes ascend and descend test maneuvers with TB47S batteries (smaller mass) and forward flight maneuvers along the triangles with TB48S batteries (larger mass). For this model, some of the K c results are invalid, giving negative values, so only the positive results were considered in further calculation. The invalid values are at the smallest V a z part, so there was not enough excitation of the model.
The tabular data are visualized in Figure 28. The figure shows that most of the maneuvers were performed with negative V a z (drone motion relative to air), meaning ascension or forward motion with high pitch angles (high velocity). There were two outliers in the data in the first flight campaign: the 7.2495 and 9.4385 values, which were removed from data union (see the figure). The figure shows that there are many more data points for negative V a z values than for positive. What is more, only the positive V a z value is about 3 m/s (descend). Thus, the characteristic for positive velocity is uncertain. Considering the range of thrust coefficients (1.5–4.5) in the negative V a z range suggests that the two Flight 1 points in the positive range are outliers. This is underlined by the finally selected symmetric fit, which has much lower values. First, an asymmetric second-order curve was fit to the data:
K c ( V a z ) = 0.0715 V a z 2 + 0.3091 V a z + 3.0277
However, later testing the vertical control of the model (after identification of the vertical controller, see Section 8.1) showed that with this asymmetric model, the output does not fit the flight measured data. This is illustrated by Figure 29, showing the differences (slower settling) in V D vertical speed tracking with the asymmetric model (compare it to Figure 52). That is why a symmetric model was fit considering only the negative V a z range, as there were more measurement points:
K c ( V a z ) = 0.0243 V a z 2 + 2.8851
Figure 30, Figure 31 and Figure 32 show the flight measured Δ f z = m a z + c T 0 6 ρ A R 2 Ω 2 ¯ forces and the outputs of the K c ( V a z ) 100 V a z 6 ρ A R Ω ¯ model for 3 m/s ascend and descend maneuvers. Figure 30 for a 3 m/s ascend shows that the symmetric model output is closer to the measured values than the asymmetric. Figure 31 for a 3 m/s descend maneuver shows that neither of the models cover the measured data well.
However, for another 3 m/s descend in the same flight test campaign, Figure 32 shows that the models cover the data, the symmetric model having a smaller average error. So for the case in Figure 31, possibly some windgust disturbance occurred, which is not considered in the model.
As a quality measure, the time-averaged absolute percentage model error was applied (23). The measures for the three figures are summarized in Table 15.
e = i | y m e a s i y m o d e l i | | y m e a s i | 100
The table shows that except for the disturbed case when both models fail, the symmetric model gave better results. These results underline that the symmetric model is better, so it is applied in the final M600 simulation.

6.3. Horizontal Torque Model Identification

The postulated model is presented in (11). Combining it with the rotational dynamics (2) results in (24).
J x p ˙ = q r ( J y J z ) q J r ( Ω L B + Ω L F Ω L S Ω R B Ω R F + Ω R S ) + c T 0 ρ A R 2 l 2 ( Ω L B 2 + Ω L F 2 + 2 Ω L S 2 Ω R B 2 Ω R F 2 2 Ω R S 2 ) + K c ( V a z ) 100 V a z ρ A R l 2 ( Ω L B + Ω L F + 2 Ω L S Ω R B Ω R F 2 Ω R S ) K p p | p | J y q ˙ = p r ( J z J x ) + p J r ( Ω L B + Ω L F Ω L S Ω R B Ω R F + Ω R S ) + c T 0 ρ A R 2 3 l 2 ( Ω L B 2 + Ω L F 2 Ω R B 2 + Ω R F 2 ) + K c ( V a z ) 100 V a z ρ A R 3 l 2 ( Ω L B + Ω L F Ω R B + Ω R F ) K q q | q |
In (24), the first four terms on the right-hand side are known from angular rate measurement, inertia and vertical force identification. On the left-hand side, smoothed numerical differentiation from [38] was applied to calculate p ˙ , q ˙ so those are also known. Theoretically, only the air drag terms ( K p , K q ) should be identified. Subtracting the known terms of the right-hand side gives residual terms ( Δ L for roll and Δ M for pitch) which should be covered with the air drag. The residuals were far from zero and the air drag component (plotted with K p = 10 , K q = 10 ) had a completely different characteristic, so it was impossible to cover the residuals with any constant K p , K q as Figures 34–36 show. So, additional model terms were required. Several combinations of V a x , V a y , Ω i , ϕ , θ , V a , and W were tested to find something characteristically similar to the residuals. Finally, the wind disturbance-based models below were postulated to cover the residuals, as they were very similar to the residual characteristic (see Figures 34–36).
K W p W l 200 ( Ω L B + Ω L F + 2 Ω L S Ω R B Ω R F 2 Ω R S ) K W q W 3 l 200 ( Ω L B + Ω L F Ω R B + Ω R F )
here, W = W N 2 + W E 2 is the Euclidean norm of the wind disturbance and K W p , K W q are gains to be determined. From engineering intuition, it would be better to apply the airspeed V a = V a x 2 + V a y 2 instead of the wind speed W ; however, it gave unacceptable results. To successfully determine the gains, persistently excited flight sections were required, which were inside a short time range to have a valid constant wind disturbance assumption and thus apply the estimated constant wind values. Hover, 5 m/s, 10 m/s, 14 m/s, + 180 yaw and 180 yaw maneuvers were considered from the flights, forming different combined data sets from them to give a wide range of excitation. Parameters estimated from the F T 1 flight campaign are shown in Table 16; those from F T 2 are in Table 17 together with the average values. Note that multiple take-offs were considered from the first flight campaign.
The average data showed that the gain is wind strength dependent, so polynomials were fitted to the W K W curves. Raw data and fitted polynomials are shown in Figure 33.
Figure 33 shows that a negative second-order function can possibly well cover the data. This is underlined by the resulted best fit (measured by mean squared error) expressions ( W = W ):
K W q = 0.2 W 2 + 2.46 W 9.39
K W p = 0.183 W 2 + 2.3 W 9.136
Some illustrative results with the averaged parameters are plotted in Figure 34, Figure 35 and Figure 36, showing acceptable coverage of the residuals by the fitted model.
However, during simulation testing, this model form gave instabilities, so finally, the fitted additional term (with K W ) was removed, but air drag effects 10 p | p | and 10 q | q | were added, resulting in the final roll and pitch dynamic models (26). The 10 coefficient of air drag was heuristically tuned based on the damping behavior of the model for roll and pitch excitation.
τ x = q J r ( Ω L B + Ω L F Ω L S Ω R B Ω R F + Ω R S ) + c T 0 ρ A R 2 l 2 ( Ω L B 2 + Ω L F 2 + 2 Ω L S 2 Ω R B 2 Ω R F 2 2 Ω R S 2 ) + K c ( V a z ) 100 V a z ρ A R l 2 ( Ω L B + Ω L F + 2 Ω L S Ω R B Ω R F 2 Ω R S ) 10 p | p | τ y = p J r ( Ω L B + Ω L F Ω L S Ω R B Ω R F + Ω R S ) + c T 0 ρ A R 2 3 l 2 ( Ω L B 2 + Ω L F 2 Ω R B 2 + Ω R F 2 ) + K c ( V a z ) 100 V a z ρ A R 3 l 2 ( Ω L B + Ω L F Ω R B + Ω R F ) 10 q | q |
Identification of the roll and pitch controllers was flawless for this model, which was similar to the final roll and pitch behavior of the DJI M600 simulation model. Thus, model mismatch from the neglection of this effect (questionable from an engineering point of view) was accepted.

6.4. Yaw Torque Model Identification

The yaw torque model is postulated in (13) together with the assumption that the hover speed of the motors is the same, so the hover parts cancel out (14).
However, the voltages of the motors differ from each other as shown, e.g., in Figure 37. As engine speed is proportional to voltage (see, e.g., [33]), this means that the hover speeds were not the same, so the mean hover speed effects were subtracted from the model before identification. This was because only the engine angular rate changes, causing the yaw rotation, should be considered to have a model relative to the hover state (see the control structure in Figure 5). The considered averaged hover values are shown below:
T c P 0 = ρ A R 3 ( Ω L B 0 2 Ω L F 0 2 + Ω L S 0 2 + Ω R B 0 2 + Ω R F 0 2 Ω R S 0 2 ) / 100 ¯ T K p = ρ A V a z R 2 ( Ω L B 0 Ω L F 0 + Ω L S 0 + Ω R B 0 + Ω R F 0 Ω R S 0 ) ¯
Subtracting the hover terms from the τ z torque (13) and considering the rotational dynamics (2) resulted in the complete yaw dynamics (28).
J z r ˙ = p q ( J x J y ) + c P 0 ρ A R 3 100 ( Ω L B 2 Ω L F 2 + Ω L S 2 + Ω R B 2 + Ω R F 2 Ω R S 2 ) T c P 0 + K p ρ A V a z R 2 ( Ω L B Ω L F + Ω L S + Ω R B + Ω R F Ω R S ) T K p K r r | r |
In the above model, the unknowns were c P 0 , K p and K r ; however, hover and ± 180 yaw rotation maneuvers were applied to identify the model parameters and the M600 held position during these maneuvers, so the V a z velocity was small and was not properly excited. On the contrary, during FAW or FWW maneuvers, the vertical rotation was zero. So finally, the K p term was removed from the model together with p q ( J x J y ) , while the measured term was negligibly small (see Figure 38, Figure 39 and Figure 40) due to the almost zero roll and pitch rates in hover or vertical rotation.
Parameter identification was completed with the least squares (LS) method selecting hover sections followed by positive and negative yaw rotations, so three flight sections/data sets were considered. The results are summarized in Table 18, including both FT1 and FT2 results. The table shows that the parameters are close to each other in one flight, and the c P 0 values are globally close to each other. The K r values are more uncertain, showing that the dominant term is c P 0 . Finally, the averaged values were applied as they gave satisfactory results shown in Figure 38, Figure 39 and Figure 40. In the figures, J z d r is the left side with inertial torque, ’Inertial’ means the p q ( J x J y ) term and ’Model’ is the output of the postulated model with average identified parameters. The figures show the negligible value of the p q ( J x J y ) inertial term and the good fit of the model both for hover and yaw rotations. Again, the performance measures (23) were too large to make a proper model selection, while the qualitative fit can be seen in the figures.

7. Control System Identification

After identifying the dynamic and aerodynamic parts of the system model, the factory DJI control loops were identified, considering the possibilities of OSDK control summarized in Table 1.
As vertical and yaw control can be identified in the position hold model and thus are relatively independent from the horizontal motion of the drone, they were identified first. The horizontal control of the drone was only identified after. In most of the cases, transfer function identification was completed on noisy measured data, so the goal was only to cover the characteristic dynamics without considering turbulence and noise effects in the models.

7.1. Vertical Control Identification

The altitude controller structure is postulated and discussed in Section 3.3 in Figure 10. It was straightforward to generate the vertical speed reference from the altitude error with a proper gain and saturation. Upon the step change of the altitude reference, there was a large step change in altitude error, so the maximum saturation of V D (this case 3 m/s) was immediately activated. Thus, the altitude error to V D reference gain could only be identified in the sections where the altitude approached the reference, and so the scaled error decreased below the saturation limit. These sections were cut out from the flight data, and an LS optimal gain fit was performed, resulting in K a l t = 0.3769 for F T 1 and K a l t = 0.3865 for F T 2 . The method is illustrated in Figure 41. The difference between the two gains is about 2.5%, so the average value can be applied:
K a l t = 0.3817
The engine speeds can be generated directly from the V D tracking error, assuming that the engine dynamics is included in the controller. For the identification of the controller, two ascend–descend sections were selected from F T 1 and two ascend sections were selected from F T 2 . Note that while there was hovering between ascend and descend in the first campaign, there was an immediate transition to descend in the second, as shown in Figure 42, so in this case, only the ascend dynamics were considered for identification.
Continuous time controller transfer function identification was completed using the Matlab tfest function with the vertical speed error as input and the average engine speed (between the six engines) relative to the hover average value as output. The denominator order was selected by trial and error, and a second-order denominator gave acceptable results for all flights (1, 2 for the first campaign and 3, 4 for the second):
G V D E 1 = 23.27 s 8.273 s 2 + 1.023 s + 0 , 55.44 %
G V D E 2 = 16.53 s 10.76 s 2 + 0.9894 s + 0 , 64.2 %
G V D E 3 = 21.99 s 13.16 s 2 + 1.395 s + 0 , 55.05 %
G V D E 4 = 7.688 s + 0.5073 s 2 + 1.523 s + 0 , 7.9 %
The parameters were close to each other, and integral controllers resulted as expected; however, the numerator of G V D E 4 was an outlier (more than 30% difference from the other parameters). This was underlined by the fit measures provided by Matlab compare function. The measure of G V D E 4 was much lower, while the others were close to each other. G V D E 2 gave the best measure, but the first numerator coefficients are closer to each other in cases of G V D E 1 , G V D E 3 obtained, respectively, from F T 1 and F T 2 . That is why, finally, an average function was calculated from G V D E 1 , G V D E 2 , G V D E 3 to balance the disturbance effects between the different flights.
G V D E = 20.6 s 10.731 s 2 + 1.1358 s = 9.448 ( 1.9197 s + 1 ) 0.88 s 2 + s
A detailed evaluation of the result (test on flight data) led to the decrease of the time constant from T = 0.88 s to T = 0.5 s . The fit quality values of the final controllers are presented in Table 19 giving balanced performance for F T 1 but worse and unacceptable values for F T 2 . The worst value is about 0 % , but Figure 43 shows that the trend of the function is acceptable. The best fit is presented in Figure 44.

7.2. Yaw Control Identification

The yaw control model is postulated in Section 3.3 in Figure 11. For this identification, ± 180 rotations from the first flight campaign ( F T 1 ) and the largest rotations from the second ( F T 2 ) were selected. As the latter used a triangular flight pattern, there were no 180 rotations. As ± 180 rotation means opposite orientation, the roll and pitch values required to maintain hover against the wind swap with each other, which also means a change in the engine speeds. As on the F T 1 flight test, there was high wind speed; this effect was significant. So in this case, the yaw control engine speed components were calculated by subtracting a spatially changing engine speed characteristic whose value depend on the northeast angular positions of the engines. That is why first, the NE angular positions of the engines (body positions are shown in Figure 8) and their speeds were registered before (at 38 M600 yaw angle) and after (at 142 M600 yaw angle) the yaw rotations and plotted in Figure 45 and Figure 46. The figures show that the average values give a close to sinusoidal change, so a sinusoidal curve was fitted as Ω 0 ( φ ) = 275 43 sin ( φ + 70 ) where φ is the engine actual angular position in the NE system. The engine speeds for yaw identification were calculated relative to this curve. In case of the second flight campaign F T 2 , the wind was very low, so no such compensation was required.
In the next step, the yaw angle step references were estimated (in F T 1 and F T 2 , UgCS-generated trajectories were used, so the onboard DJI references were not known) considering the flight yaw angle changes and the start of yaw rate changes. A constant gain was applied to generate the yaw rate reference from the yaw angle error considering the yaw rate saturations, which are 0.72 rad/s and 1.605 rad/s for F T 1 and + 1.92 rad/s and 1.745 rad/s for the F T 2 flight campaign (set by the DJI system independently from the user). K ψ = 2 was the first result but finally, tuning with yaw control simulation K ψ = 1.5 gave satisfactory results as Figure 47 shows. For unlimited applicability, the yaw angle error ψ r e f ψ should be checked for unrealistic large values upon changes from 180 to 180 or vice versa. This is denoted by the ± π in the K ψ gain block in Figure 11.
After generating the yaw rate reference from the angle error, the yaw rate error to engine speed (relative to the hover speeds) transfer functions were identified. Considering the engine rotational directions in Figure 8, their reaction torques are opposite to the rotation so RF, RB, LS engines give positive torques and RS, LF, LB give negative torques. That is why the controller dynamics were identified separately for these two groups ( G r E + and G r E ), again applying the Matlab tfest function with second-order transfer function denominators. However, first the delay between the yaw rate error and engine speed output in the measured data was corrected, being about 0.26 s in all flights. Later (see Section 8), detailed delay analysis was applied, resulting in a separate yaw angle and yaw rate reference delays, as shown in Figure 11.
The transfer function identification results are shown in Table 20 with averaged functions for the two + 180 and 180 rotations. Four sets from each flight campaign were considered.
Regarding the G r E + results, the numerator gains were close to each other except for the fourth case where the numerator was negative and thus invalid. The gains for the G r E case were also similar to the G r E + case, too. However, the numerator time constants were very different for G r E + , while for G r E , the 1 and 4 and the 2 and 3 numerator time constants were similar. Regarding the denominator time constants, there were slower (above 0.1 s) and faster (below 0.1 s) values. Finally, after evaluating and tuning on all of the data sets to obtain the best overall results, the following form was fixed:
G r E = ± 97.2 ( s + 0.3 ) s ( 0.0767 s + 1 )
The fit qualities are shown in Table 21. The best result (Set 5/ G r E with 70.45 % fit quality) and worst result (Set 1/ G r E with 24.13 % fit quality) are plotted in Figure 48 and Figure 49, respectively. Considering the amplitudes, the worst result is also acceptable, only it is delayed at the beginning. Overall, the fit quality is above 40–50% in most of the cases.

7.3. Horizontal Velocity Control Identification

The horizontal control structure is postulated in Section 3.3 in Figure 9. After saturating the velocity reference, pitch or roll angle references (depending on tangential or normal control) should be generated from the velocity error. However, as the wind disturbances must be compensated with nonzero pitch and roll angles, a PI controller was required for this task to be able to hover with zero velocity (and so nonzero angles). Integral control requires AW ( θ m a x = ϕ m a x = 25 ) to quickly react with the angles for any changes. However, this introduced a switching nonlinearity into the system, making closed-form transfer function identification impossible. That is why the PI gains were tuned by trial-and-error. There was an attempt to identify the pitch (roll) angle error to engine speed control dynamics subtracting hovering engine speeds, but the results were unsatisfactory when tested in simulation. So, finally, two-step tuning was performed after building a longitudinal simulation including altitude and pitch dynamics.
The postulated angle-tracking controller transfer function was similar to G a l t and G ψ without the integral effect (as the engine speeds generate torque and thus angular acceleration, the system has integral property):
G θ = g ( T d s + 1 ) T s + 1
Note that for pitch control, only the front and back four engines were applied with negative controller dynamics for the back ones. In roll control, the right engine reactions were considered negative. First, the g gain (pure P controller) was tuned to have a proper initial response g = 100 , which was satisfactory. Then, the time constant T and derivative effect T d were tuned to have short settling time (pitch (roll) control is the innermost loop, so it should be fast) without oscillations, T = 0.01 s was satisfactory together with T d = 0.1 s , so the final control transfer function (both for pitch and roll) is:
G θ ( ϕ ) = 100 ( 0.1 s + 1 ) 0.01 s + 1
After identifying the pitch (roll) error to engine speed control dynamics, the gains of the PI AW controller generating the reference angles from the velocity error were determined applying the longitudinal control model again by trial-and-error to fit flight data with model outputs. Finally, P = 0.07 and I = 0.03 constant gains were determined with negative signs in case of tangential control (there, a negative pitch down causes positive forward velocity).
After finishing the whole system identification, SIL simulation (provided by DJI) and flight data-based validation and refinement of the model were performed.

8. SIL and Flight Data-Based Verification, Refinement and Special Modes

After identifying the system dynamics and the control loops, the Matlab Simulink 3D simulation model was constructed considering the full 6DoF rigid body motion of the drone (see Figure 4 in Section 3). After model construction, model validation and refinement are required, which was completed running the simulation model with the same OSDK reference inputs as in SIL and real flight and comparing the results. The flight test part was based completely on the F T 3 flight campaign, whose data were not applied in the identification process, so this provided the validation of the model. Of course, the model was initialized for the initial flight state. The next sections show the identified model outputs and discuss the refinements, presenting the finally applied model and its outputs compared to SIL and flight data. First, the inner and then the outer control loops were refined.

8.1. Vertical Control

First, the tracking of the vertical velocity reference of the model (SIM in the figures) was compared to SIL and flight test results applying the controller in (29). The results are shown in Figure 50 and Figure 51. The figures show that the model was too slow with large overshoot, and there was a delay in both SIL and flight tracking, which was not present in the simulation model. Thus, the gain of the controller was increased, and the numerator time constant decreased as (33) shows. Additionally, a 0.07 s delay was applied at the V D r e f reference, as shown in Figure 10. The improved tracking results are shown in Figure 52 and Figure 53. The figures show that the tracking became very similar to SIL and flight results, though not all of the delay was modeled at the beginning of the reference. However, at the other transients, the delay difference is smaller.
G V D E = 18 ( 2 s + 1 ) 0.1 s 2 + s
After fine tuning the vertical velocity tracking control, the altitude tracking was tested again by comparison to SIL and flight results (see Figure 54 and Figure 55). The figures show that both altitude and vertical velocity dynamics are very similar to SIL and flight, so there is no need to change the K a l t gain and the method of vertical velocity reference generation or the controller.

8.2. Yaw Control

In case of yaw control, first, the yaw rate tracking was evaluated and fine tuned. Unfortunately, the yaw rate was only saved onboard the drone, and this log file was damaged during the SIL test, so only the comparison to flight test results was possible.
Figure 56 shows the yaw rate tracking with controller from (30) and zero reference delay. The figure shows that the model was slow and did not converge fast enough in case of larger yaw rate reference. Thus, the controller time constant was decreased, and the gain increased, resulting in (34). Also, 0.02 s delay was added to the yaw rate reference based on detailed evaluation of the data. The improved yaw rate tracking is shown in Figure 57 with fast increase and settling.
G r E = 200 ( s + 0.3 ) 0.06 s 2 + s
After tuning the yaw rate inner loop, the yaw angle tracking control was evaluated first, with a K ψ = 1.5 yaw angle error to yaw rate gain. Figure 58 shows that the tracking was slow and did not have any overshoot. So finally, K ψ = 2.5 was applied, reproducing the fast dynamics but without overshoot (note that the first identified parameter was K ψ = 2 closer to the final value; see Section 7.2). With larger K ψ , part of the overshoots could be reproduced but with too fast dynamics. Thus, finally, the dynamics similar to SIL and flight was preserved, sacrificing the overshoot. The tracking results of the final control are shown in Figure 59 together with the yaw rate dynamics in Figure 60. The latter shows a faster increase in yaw rate and the lack of overshoot.

8.3. Horizontal Control

First, the roll and pitch angle tracking control was verified, and the handling of the special mode discussed in Section 4.1.2 was solved. The final tracking results are presented in Figure 61 and Figure 62. The normal tracking of the angle references worked well with the identified model (see (32)), giving even slightly better results than the SIL simulation (compared to the flight response). Only 0.07 s delay was added to the angle references. The special mode includes switching from angle reference tracking to zero velocity reference tracking, and also the increase in velocity tracking gain was observed, meaning that a braking mode is activated in this case. The figures show that even this braking mode behavior is well described by the model having outputs close to the SIL results.
Zero velocity tracking is switched in the model when the OSDK control is switched to angle tracking mode and both roll and pitch references are zero. The activation of the braking mode is more complex, following the rules below:
  • If V r e f = 0 and | V | > 1 (consequently | Δ V | > 1 ) and the controller is in normal velocity tracking mode: switch braking mode meaning upscale of the P gain P = 1.8 P and zeroing out the integral state of the PI controller.
  • If | Δ V | < 1 and controller is in braking mode: switch back to normal tracking mode by applying the P gain again (integral state remains unchanged)
So, the braking mode is activated when the commanded velocity is zero, the velocity tracking error is large and even the velocity itself is large. Note that this is why the Δ V velocity tracking error is an input of the velocity tracking PI controllers (see Figure 9).
After validating the roll and pitch angle control and its special mode, tangential and normal velocity tracking control were evaluated. The results are shown in Figure 63, Figure 64, Figure 65 and Figure 66. Figure 63 and Figure 64 show that the velocity tracking is pretty good with the original identified P = 0.07 and I = 0.03 parameters; even the overshoots are reproduced well. The only difference is the earlier settling of the model to nonzero values and a later settling to zero values, but both are acceptable.
Figure 65 and Figure 66 show that the roll and pitch angles are also reproduced well by the model being closer to the flight data than to SIL results. Note that the flight data are shifted due to the roll and pitch compensation of wind disturbances. Shifting its theoretically zero sections back to zero, the nonzero sections approach the model output.

8.3.1. Position Kick Control Identification

The position kick control is a special mode as discussed in Section 4.1.1. Flight and SIL testing showed that for a position kick reference, the drone accelerates to some velocity (as tracking a half-doublet speed reference) and then stops; for a step position reference, the drone keeps a constant velocity. The questions were the length and value of the half-doublet velocity reference and the value of the constant velocity reference.
Analysis of different position kick tracking maneuvers showed that the value of the half-doublet velocity reference is the value of the position kick signal. Its length was identified through a series of inverse model calculations applying SIL simulation data, as it is not affected by wind disturbance, and its validity for this maneuver was verified in Section 4.1.1 as Figure 15 shows. First, the transfer functions from pitch and roll references ( 8 9 to avoid any saturation in the system) to pitch and roll angles were identified (with Matlab tfest function) giving two similar functions with 97.02% and 97.15% fit quality:
G θ r e f θ = 104.8 s 2 + 13.87 s + 121.1 , G ϕ r e f ϕ = 103.4 s 2 + 14.6 s + 119.3
The two functions and their fit quality were very close to each other, so their average was considered as
G = 104.1 s 2 + 14.235 s + 120.2
As the inner references of the DJI controller could not be logged, the inverse of this transfer function was applied to estimate the pitch and roll references in position kick flight from the pitch and roll angle outputs. As the transfer function was stable, its inverse could be calculated giving an improper function, but its execution in discrete time was feasible.
After estimating the pitch and roll references, they were smoothed, and the inverse of the PI controller (generating angle references from velocity error) was applied to estimate the velocity references generated by the position kick control. The length of the half-doublet velocity reference was estimated based on this signal and resulted as 0.65 s . Plots of the main steps are shown in Figure 67 and Figure 68.
Figure 67 shows the raw and smoothed estimated pitch reference and the transfer function output driven by the smoothed reference compared to the SIL simulation output. The model pitch output is very close to the SIL one. Figure 68 shows the estimated velocity reference and the generated one based on the width of the estimated signal covering only the first half-doublet wave. The second half is not required to generate a behavior similar to the real system. The pitch references and dynamics are also plotted comparing the smoothed estimated reference to the one generated from the velocity reference and the SIL and model outputs. Comparison of the outputs shows that qualitatively they are similar, but the values are different from each other.
Refinement and final validation of this model was performed on the full 3D simulation of M600, resulting in 0.75 s width of the velocity reference, giving better results in velocity and position responses. Figure 69 shows the position transients after a tangential kick command. The figure shows that the maximum value of the position move is about the same as in SIL, but the model moves back after reaching the maximum distance. This is caused by a transient of the velocity shown in Figure 70 and could not be removed from the model. The figure also shows that the maximum velocities are about the same as in SIL. The width of the velocity reference was increased to achieve this state. Finally, Figure 71 shows the pitch angle reference and transients having similar peak values and dynamics. As this position kick mode is not the most practical and important one, model refinement was finished at this stage.
Regarding the application of step position reference ( P r e f ) instead of the position kick command SIL and flight data analysis showed that for smaller position references, half of them were set as reference velocity, but for larger references, the velocity was limited to 3 m/s, so finally the reference velocity model was:
V r e f = s i g n P r e f min | P r e f | 2 , 3
both in tangential and normal direction.

8.3.2. Control in Northeast Directions

In Table 1, the HORIZONTAL_GROUND option means that the horizontal position, velocity or angle references should be implemented along north and east earth coordinate system axes. Although the system identification was performed with the HORIZONTAL_BODY option, this mode was also implemented in the model to extend applicability. For position and velocity references, simply the inverse of the transformation in (1) was applied. The pitch and roll angle references are now understood around the east ( α E ) and north ( α N ) axes, so the transformation matrix from a rotated body to the NED system should be constructed (based on ψ , α E , α N ) and the body referenced Euler angles (which drive the controllers in the model) obtained from it. The rotation steps are as follows. Rotation from body to NED:
T ψ = c o s ( ψ ) s i n ( ψ ) 0 s i n ( ψ ) c o s ( ψ ) 0 0 0 1
Rotation around the north axis (ground ‘roll’ rotation):
T N = 1 0 0 0 c o s ( α N ) s i n ( α N ) 0 s i n ( α N ) c o s ( α N )
Rotation around the east axis (ground ‘pitch’ rotation):
T E = c o s ( α E ) 0 s i n ( α E ) 0 1 0 s i n ( α E ) 0 c o s ( α E )
The final rotation from the transformed body to NED system results as:
T E B = T E T N T ψ
The body referenced Euler angles can be obtained from this and applied in the tangential-normal control setup. After identification, verification and refinement of the dynamics and control loops the conclusion can be drawn.

9. Conclusions

This paper presents the high-fidelity simulation model identification of a DJI M600 Pro hexacopter, including not only system but also controller dynamics, focusing on the OSDK (Onboard Software Development Kit) control modes and presenting even the special cases. Such a model is required in research and development projects aiming to design custom mission controllers for this drone, which is widely used by universities and research institutes.
Real flight and software-in-the-loop (SIL) test data were applied to identify the model also validating the SIL simulation provided by DJI. First, the hardware and control software structure of the drone was introduced. Then, the planned structure of the high-fidelity simulation model was presented. After introducing the three flight test campaigns and the discovered special modes first, the mass and inertial properties were measured and calculated with both battery setups (TB47S and TB48S) and a custom Forerunner UAV payload. Then, the system dynamics (including dynamic and aerodynamic effects) was identified, including horizontal forces and wind disturbances, hover and vertical forces and finally, horizontal and yaw torque dynamics based on real flight data.
After identification of the dynamics, the control loops following the structure of OSDK control possibilities were identified, including also engine dynamics. Vertical, yaw and horizontal control were considered. Before publishing the model, unused flight and SIL data-based verification and refinement was completed for vertical, horizontal and yaw control considering all OSDK control modes except for the horizontal angular rate and vertical thrust, which are the innermost control levels not required for mission planning and control and being dangerous when directly excited by a custom controller. Finally, position kick control (special implementation of horizontal position control by DJI) and the consideration of horizontal references in a northeast (Earth) coordinate system instead of the multicopter body were presented. The refinement and validation was successful; the model covers well all OSDK control modes—even the special ones.
The paper ends with an overview of the resulting high-fidelity simulation and control model implemented in Matlab Simulink as a Supplementary Materials.

Supplementary Materials

The following supporting information can be downloaded at: https://www.mdpi.com/article/10.3390/aerospace11010079/s1.

Author Contributions

Experiment design, data processing, model identification P.B.; code building, data logging, experiment execution M.N.; model implementation P.B. and M.N. All authors have read and agreed to the published version of the manuscript.

Funding

The research was supported by the European Union within the framework of the National Laboratory for Autonomous Systems. (RRF-2.3.1-21-2022-00002). Project no. TKP2021-NVA-01 has been implemented with the support provided by the Ministry of Innovation and Technology of Hungary from the National Research, Development and Innovation Fund, financed under the TKP2021-NVA funding scheme. The DJI M600 Pro research platform was provided by the “Developing innovative automotive testing and analysis competencies in the West Hungary region based on the infrastructure of the Zalaegerszeg Automotive Test Track” GINOP-2.3.4-15-2020-00009 project.

Data Availability Statement

The data presented in this study are available on request from the corresponding author. The data are not publicly available due to confidentiality reasons.

Acknowledgments

The authors gratefully acknowledge the help of Sandor Csurgai BSc student in collecting and processing simulation and in-flight system responses during his summer internship in 2022.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. UNM. The University of New Mexico, Center for Advancement of Spatial Informatics Research & Education: DJI M600 Equipment. 2023. Available online: https://aspire.unm.edu/facilities/equipment-computing/dji-m600.html (accessed on 21 December 2023).
  2. SeaBee. SeaBee Research Infrastructure: DJI M600 Pro. 2023. Available online: https://seabee.no/dji-m600-pro/ (accessed on 21 December 2023).
  3. ONERA. ONERA: DJI M600 Application. 2023. Available online: https://www.onera.fr/fr/actualites/imagerie-laser-3d-haute-resolution-embarquee-sur-drones (accessed on 21 December 2023).
  4. Sapkota, R. Using UAS Imagery and Computer Vision to Support Site-Specific Weed Control in Corn. Master’s Thesis, North Dakota State University of Agriculture and Applied Science, Fargo, ND, USA, 2021. [Google Scholar]
  5. Zhang, J.; Chadha, R.G.; Velivela, V.; Singh, S. P-CAL: Pre-computed Alternative Lanes for Aggressive Aerial Collision Avoidance. In Proceedings of the 12th International Conference on Field and Service Robotics (FSR ’19), Tokyo, Japan, 29–31 August 2019. [Google Scholar]
  6. Zhang, F.; Song, J. Real-Time Calibration of Gyro-Magnetometer Misalignment. IEEE Robot. Autom. Lett. 2018, 3, 849–856. [Google Scholar] [CrossRef]
  7. Bates, J.S.; Montzka, C.; Schmidt, M.; Jonard, F. Estimating Canopy Density Parameters Time-Series for Winter Wheat Using UAS Mounted LiDAR. Remote Sens. 2021, 13, 710. [Google Scholar] [CrossRef]
  8. Nguyen, T.M.; Yuan, S.; Cao, M.; Lyu, Y.; Nguyen, T.H.; Xie, L. NTU VIRAL: A visual-inertial-ranging-lidar dataset, from an aerial vehicle viewpoint. Int. J. Robot. Res. 2021, 41, 270–280. [Google Scholar] [CrossRef]
  9. Recalde, L.F.; Guevara, B.S.; Carvajal, C.P.; Andaluz, V.H.; Varela-Aldas, J.; Gandolfo, D.C. System Identification and Nonlinear Model Predictive Control with Collision Avoidance Applied in Hexacopters UAVs. Sensors 2022, 22, 4712. [Google Scholar] [CrossRef] [PubMed]
  10. Sa, I.; Kamel, M.; Khanna, R.; Popovic, M.; Nieto, J.I.; Siegwart, R.Y. Dynamic System Identification, and Control for a Cost Effective Open-Source VTOL MAV; Technical Report; Autonomous Systems Lab., Department of Mechanical and Process Engineering: Zurich, Switzerland, 2017. [Google Scholar]
  11. Bauer, P.; Hiba, A.; Nagy, M.; Simonyi, E.; Kuna, G.I.; Kisari, A.; Drotar, I.; Zarandy, A. Encounter Risk Evaluation with a Forerunner UAV. Remote Sens. 2023, 15, 1512. [Google Scholar] [CrossRef]
  12. Hiba, A.; Bauer, P.; Nagy, M.; Simonyi, E.; Kisari, A.; Kuna, G.I.; Drotar, I. Software-in-the-loop simulation of the forerunner UAV system. IFAC-PapersOnLine 2022, 55, 139–144. [Google Scholar] [CrossRef]
  13. Bauer, P.; Nagy, M.; Kuna, G.I.; Kisari, A.; Simonyi, E.; Hiba, A.; Drotar, I. Stability focused evaluation and tuning ofspecial ground vehicle tracking algorithms. In Proceedings of the 22nd World Congress of the International Federation of Automatic Control (IFAC WC 2023), Yokohama, Japan, 9–14 July 2023. [Google Scholar]
  14. DJI. DJI::OSDK::Control Class Reference. 2023. Available online: https://developer.dji.com/onboard-api-reference/classDJI_1_1OSDK_1_1Control.html (accessed on 21 December 2023).
  15. Kroo, I.M.; Shantz, M.; Kunz, P.; Fay, G.; Cheng, S.J.; Fábián, T. The Mesicopter: A Miniature Rotorcraft Concept Phase II Interim Reporbt; Technical Report; Stanford University: Stanford, CA, USA, 2001. [Google Scholar]
  16. Bouabdallah, S. Design and Control of Quadrotors with Application to Autonomous Flying. Ph.D. Thesis, École Polytechnique Fédérale de Lausanne, Lausanne, Switzerland, 2007. [Google Scholar] [CrossRef]
  17. Fogelberg, J. Navigation and Autonomous Control of a Hexacopter in Indoor Environments. Master’s Thesis, Lund University, Lund, Sweden, 2013. [Google Scholar]
  18. Kaya, D.; Kutay, A. Modeling, Simulation, and System Identification of a Quadrotor Helicopter. In Proceedings of the 7th Ankara International Aerospace Conference, Ankara, Turkey, 11–13 September 2013. [Google Scholar]
  19. Capello, E.; Park, H.; Tavora, B.; Guglieri, G.; Romano, M. Modeling and experimental parameter identification of a multicopter via a compound pendulum test rig. In Proceedings of the 2015 Workshop on Research, Education and Development of Unmanned Aerial Systems (RED-UAS), Cancún, México, 23–25 November 2015; pp. 308–317. [Google Scholar] [CrossRef]
  20. Reséndiz, V.M.A.; Rivas-Araiza, E.A. System Identification of a Quad-rotor in X Configuration from Experimental Data. Res. Comput. Sci. 2016, 118, 77–86. [Google Scholar] [CrossRef]
  21. Bangura, M. Aerodynamics and Control of Quadrotors. Ph.D. Thesis, Australian National University, Canberra, Australia, 2017. [Google Scholar]
  22. Ivler, C.M.; Rowe, E.S.; Martin, J.; Lopez, M.J.S.; Tischler, M.B. System Identification Guidance For Multirotor Aircraft: Dynamic Scaling and Test Techniques. In Proceedings of the Vertical Flight Society’s 75th AnnualForum & Technology Display, Philadelphia, PA, USA, 13–16 May 2019. [Google Scholar]
  23. Rosales, C.; Soria, C.M.; Rossomando, F.G. Identification and adaptive PID Control of a hexacopter UAV based on neural networks. Int. J. Adapt. Control Signal Process. 2019, 33, 74–91. [Google Scholar] [CrossRef]
  24. Yuksek, B.; Saldiran, E.; Cetin, A.; Yeniceri, R.; Inalhan, G. System Identification and Model-Based Flight Control System Design for an Agile Maneuvering Quadrotor Platform. In Proceedings of the AIAA Scitech 2020 Forum AIAA, Orlando, FL, USA, 6–10 January 2020. [Google Scholar] [CrossRef]
  25. Niemiec, R.; Ivler, C.; Gandhi, F.; Sanders, F. Multirotor electric aerial vehicle model identification with flight data with corrections to physics-based models. CEAS Aeronaut. J. 2022, 13, 575–596. [Google Scholar] [CrossRef]
  26. DJI. DJI M600 Pro Hexacopter. 2017. Available online: https://www.dji.com/hu/matrice600-pro (accessed on 21 December 2023).
  27. Engineering, S. SPH Engineering: UgCS Professional Drone Mission Planning Software. 2023. Available online: https://www.sphengineering.com/flight-planning/ugcs (accessed on 21 December 2023).
  28. Ducard, G.; Hua, M.D. WCA: A New Efficient Nonlinear Adaptive Control Allocation for Planar Hexacopters. IEEE Access 2023, 11, 37714–37748. [Google Scholar] [CrossRef]
  29. Beard, R.W.; McLain, T.W. Small Unmanned Aircraft; Princeton University Press: Princeton, NJ, USA, 2012. [Google Scholar]
  30. Bouabdallah, S.; Siegwart, R. Full control of a quadrotor. In Proceedings of the 2007 IEEE/RSJ International Conference on Intelligent Robots and Systems, San Diego, CA, USA, 29 October–2 November 2007; pp. 153–158. [Google Scholar] [CrossRef]
  31. Damaren, C.J.; Kolaei, A.; Barcelos, D.; Bramesfeld, G. Experimental Analysis of a Small-Scale Rotor at Various Inflow Angles. Int. J. Aerosp. Eng. 2018, 2018, 2560370. [Google Scholar] [CrossRef]
  32. Nagy, M. Development and Simulation Testing of a Forerunner UAV System. Master’s Thesis, Budapest University of Technology and Economics, Budapest, Hungary, 2021. [Google Scholar]
  33. DJI. E2000 Pro Tuned Propulsion System Manual. 2016. Available online: https://dl.djicdn.com/downloads/e2000/20161220/E2000+Pro+User+Manual+V1.4.pdf (accessed on 21 December 2023).
  34. DJI. DJI OSDK Flight Control Sample. 2023. Available online: https://developer.dji.com/onboard-sdk/documentation/sample-doc/flight-control.html (accessed on 21 December 2023).
  35. Bauer, P.; Nagy, M.; Csurgai, S. Simulation Model Verification and Special ControlModes of DJI M600 Pro Multicopter. In Proceedings of the Submitted to the 12th International Conference on Mechatronics and Control Engineering (ICMCE 2024), Budapest, Hungary, 25–27 January 2024. [Google Scholar]
  36. Onshape Free CAD Platform. Available online: https://www.onshape.com/en/products/free (accessed on 11 January 2024).
  37. Hornik, V. Windguru Website. Available online: https://www.windguru.cz (accessed on 11 January 2024).
  38. Morelli, E. System Identification Programs for AirCraft (SIDPAC). In Proceedings of the AIAA Atmospheric Flight Mechanics Conference and Exhibit, Monterey, CA, USA, 5–8 August 2002. [Google Scholar] [CrossRef]
Figure 1. DJI M600 Pro Forerunner UAV platform with extra payload systems.
Figure 1. DJI M600 Pro Forerunner UAV platform with extra payload systems.
Aerospace 11 00079 g001
Figure 2. Block scheme of the drone onboard hardware in the Forerunner UAV setup.
Figure 2. Block scheme of the drone onboard hardware in the Forerunner UAV setup.
Aerospace 11 00079 g002
Figure 3. Onboard hardware system of the aerial vehicle. 1: RTK GNSS electronics, 2: Basler camera, 3: Gimbal, 4: WiFi antennas, 5: Nvidia Jetson Xavier NX, 6: 4S LiPo battery.
Figure 3. Onboard hardware system of the aerial vehicle. 1: RTK GNSS electronics, 2: Basler camera, 3: Gimbal, 4: WiFi antennas, 5: Nvidia Jetson Xavier NX, 6: 4S LiPo battery.
Aerospace 11 00079 g003
Figure 4. Block diagram of DJI M600 Pro 6DoF simulation model.
Figure 4. Block diagram of DJI M600 Pro 6DoF simulation model.
Aerospace 11 00079 g004
Figure 5. Block diagram of identified DJI M600 controller implementing OSDK modes.
Figure 5. Block diagram of identified DJI M600 controller implementing OSDK modes.
Aerospace 11 00079 g005
Figure 6. The applied coordinate systems.
Figure 6. The applied coordinate systems.
Aerospace 11 00079 g006
Figure 7. The body coordinate system on M600.
Figure 7. The body coordinate system on M600.
Aerospace 11 00079 g007
Figure 8. Engines, their angular positions and their rotational directions in body system of DJI M600.
Figure 8. Engines, their angular positions and their rotational directions in body system of DJI M600.
Aerospace 11 00079 g008
Figure 9. Scheme of tangential velocity controller.
Figure 9. Scheme of tangential velocity controller.
Aerospace 11 00079 g009
Figure 10. Scheme of altitude controller.
Figure 10. Scheme of altitude controller.
Aerospace 11 00079 g010
Figure 11. Scheme of yaw angle controller.
Figure 11. Scheme of yaw angle controller.
Aerospace 11 00079 g011
Figure 12. Straight back and forth flight trajectories.
Figure 12. Straight back and forth flight trajectories.
Aerospace 11 00079 g012
Figure 13. Triangle flight trajectories.
Figure 13. Triangle flight trajectories.
Aerospace 11 00079 g013
Figure 14. Effect of position kick command on position.
Figure 14. Effect of position kick command on position.
Aerospace 11 00079 g014
Figure 15. Effect of position kick command on velocity and angle.
Figure 15. Effect of position kick command on velocity and angle.
Aerospace 11 00079 g015
Figure 16. Pitch doublet command response.
Figure 16. Pitch doublet command response.
Aerospace 11 00079 g016
Figure 17. Roll doublet command response.
Figure 17. Roll doublet command response.
Aerospace 11 00079 g017
Figure 18. Stock DJI M600 3D model for inertia calculation.
Figure 18. Stock DJI M600 3D model for inertia calculation.
Aerospace 11 00079 g018
Figure 19. Payload DJI M600 3D model for inertia calculation: top view with additional GPS antenna.
Figure 19. Payload DJI M600 3D model for inertia calculation: top view with additional GPS antenna.
Aerospace 11 00079 g019
Figure 20. Payload DJI M600 3D model for inertia calculation: bottom view with onboard computer, GPS module, gimbal and camera.
Figure 20. Payload DJI M600 3D model for inertia calculation: bottom view with onboard computer, GPS module, gimbal and camera.
Aerospace 11 00079 g020
Figure 21. Weather and wind forecast for 14 April 2022 ( F T 2 ) (printscreen from [37]).
Figure 21. Weather and wind forecast for 14 April 2022 ( F T 2 ) (printscreen from [37]).
Aerospace 11 00079 g021
Figure 22. Longitudinal (X) forces in hover, climb, FAW and FWW flights and the outputs of the fitted model in the first flight campaign ( F T 1 ).
Figure 22. Longitudinal (X) forces in hover, climb, FAW and FWW flights and the outputs of the fitted model in the first flight campaign ( F T 1 ).
Aerospace 11 00079 g022
Figure 23. Lateral (Y) forces in hover, climb, FAW and FWW flights and the outputs of the fitted model in the first flight campaign ( F T 1 ).
Figure 23. Lateral (Y) forces in hover, climb, FAW and FWW flights and the outputs of the fitted model in the first flight campaign ( F T 1 ).
Aerospace 11 00079 g023
Figure 24. Longitudinal (X) forces in 5 m/s and 10 m/s triangle flights in the second flight campaign ( F T 2 ).
Figure 24. Longitudinal (X) forces in 5 m/s and 10 m/s triangle flights in the second flight campaign ( F T 2 ).
Aerospace 11 00079 g024
Figure 25. Lateral (Y) forces in 5 m/s and 10 m/s triangle flights in the second flight campaign ( F T 2 ).
Figure 25. Lateral (Y) forces in 5 m/s and 10 m/s triangle flights in the second flight campaign ( F T 2 ).
Aerospace 11 00079 g025
Figure 26. Engine speeds in FT1/3 hover case.
Figure 26. Engine speeds in FT1/3 hover case.
Aerospace 11 00079 g026
Figure 27. Gravitational and thrust force in hover (FT1/3 case).
Figure 27. Gravitational and thrust force in hover (FT1/3 case).
Aerospace 11 00079 g027
Figure 28. Thrust coefficient fit to all flight data.
Figure 28. Thrust coefficient fit to all flight data.
Aerospace 11 00079 g028
Figure 29. Slower settling of vertical velocity tracking with asymmetric thrust coefficient model.
Figure 29. Slower settling of vertical velocity tracking with asymmetric thrust coefficient model.
Aerospace 11 00079 g029
Figure 30. Vertical force model outputs in ascend mode.
Figure 30. Vertical force model outputs in ascend mode.
Aerospace 11 00079 g030
Figure 31. Vertical force model outputs in descend mode.
Figure 31. Vertical force model outputs in descend mode.
Aerospace 11 00079 g031
Figure 32. Vertical force model outputs in another descend mode.
Figure 32. Vertical force model outputs in another descend mode.
Aerospace 11 00079 g032
Figure 33. W K W curves and fitted polynomials.
Figure 33. W K W curves and fitted polynomials.
Aerospace 11 00079 g033
Figure 34. Roll model with averaged parameters (FWW 10 m/s flight section).
Figure 34. Roll model with averaged parameters (FWW 10 m/s flight section).
Aerospace 11 00079 g034
Figure 35. Pitch model with averaged parameters (FWW 10 m/s flight section).
Figure 35. Pitch model with averaged parameters (FWW 10 m/s flight section).
Aerospace 11 00079 g035
Figure 36. Roll model with averaged parameters (FAW 10 m/s flight section).
Figure 36. Roll model with averaged parameters (FAW 10 m/s flight section).
Aerospace 11 00079 g036
Figure 37. Engine voltages during flight.
Figure 37. Engine voltages during flight.
Aerospace 11 00079 g037
Figure 38. Yaw torque model in hover.
Figure 38. Yaw torque model in hover.
Aerospace 11 00079 g038
Figure 39. Yaw torque model in +180 degs yaw turn.
Figure 39. Yaw torque model in +180 degs yaw turn.
Aerospace 11 00079 g039
Figure 40. Yaw torque model in –180 degs yaw turn.
Figure 40. Yaw torque model in –180 degs yaw turn.
Aerospace 11 00079 g040
Figure 41. Conversion of altitude error to V D reference on selected sections (highlighted with x and o symbols).
Figure 41. Conversion of altitude error to V D reference on selected sections (highlighted with x and o symbols).
Aerospace 11 00079 g041
Figure 42. Flight altitude and the generated reference signal in flight campaigns F T 1 and F T 2 .
Figure 42. Flight altitude and the generated reference signal in flight campaigns F T 1 and F T 2 .
Aerospace 11 00079 g042
Figure 43. Worst altitude control function fit.
Figure 43. Worst altitude control function fit.
Aerospace 11 00079 g043
Figure 44. Best altitude control function fit.
Figure 44. Best altitude control function fit.
Aerospace 11 00079 g044
Figure 45. Engine speed effect of engine angular position at 38 yaw.
Figure 45. Engine speed effect of engine angular position at 38 yaw.
Aerospace 11 00079 g045
Figure 46. Engine speed effect of engine angular position at 142 yaw.
Figure 46. Engine speed effect of engine angular position at 142 yaw.
Aerospace 11 00079 g046
Figure 47. Yaw rate reference from yaw angle error and flight yaw rate.
Figure 47. Yaw rate reference from yaw angle error and flight yaw rate.
Aerospace 11 00079 g047
Figure 48. Yaw angle control model output and flight data in the best case.
Figure 48. Yaw angle control model output and flight data in the best case.
Aerospace 11 00079 g048
Figure 49. Yaw angle control model output and flight data in the worst case.
Figure 49. Yaw angle control model output and flight data in the worst case.
Aerospace 11 00079 g049
Figure 50. Comparison of vertical velocity tracking results.
Figure 50. Comparison of vertical velocity tracking results.
Aerospace 11 00079 g050
Figure 51. Zoomed start of vertical velocity tracking.
Figure 51. Zoomed start of vertical velocity tracking.
Aerospace 11 00079 g051
Figure 52. Comparison of vertical velocity tracking results with improved controller.
Figure 52. Comparison of vertical velocity tracking results with improved controller.
Aerospace 11 00079 g052
Figure 53. Zoomed start of vertical velocity tracking with improved controller.
Figure 53. Zoomed start of vertical velocity tracking with improved controller.
Aerospace 11 00079 g053
Figure 54. Comparison of altitude tracking results.
Figure 54. Comparison of altitude tracking results.
Aerospace 11 00079 g054
Figure 55. Vertical velocity tracking in altitude tracking control.
Figure 55. Vertical velocity tracking in altitude tracking control.
Aerospace 11 00079 g055
Figure 56. Yaw rate tracking.
Figure 56. Yaw rate tracking.
Aerospace 11 00079 g056
Figure 57. Yaw rate tracking with improved controller.
Figure 57. Yaw rate tracking with improved controller.
Aerospace 11 00079 g057
Figure 58. Yaw angle tracking.
Figure 58. Yaw angle tracking.
Aerospace 11 00079 g058
Figure 59. Yaw angle tracking with improved controller.
Figure 59. Yaw angle tracking with improved controller.
Aerospace 11 00079 g059
Figure 60. Yaw rate in yaw angle tracking with improved controller.
Figure 60. Yaw rate in yaw angle tracking with improved controller.
Aerospace 11 00079 g060
Figure 61. Roll angle tracking.
Figure 61. Roll angle tracking.
Aerospace 11 00079 g061
Figure 62. Pitch angle tracking.
Figure 62. Pitch angle tracking.
Aerospace 11 00079 g062
Figure 63. Tangential velocity tracking.
Figure 63. Tangential velocity tracking.
Aerospace 11 00079 g063
Figure 64. Normal velocity tracking.
Figure 64. Normal velocity tracking.
Aerospace 11 00079 g064
Figure 65. Pitch angle tracking during tangential velocity tracking.
Figure 65. Pitch angle tracking during tangential velocity tracking.
Aerospace 11 00079 g065
Figure 66. Roll angle tracking during normal velocity tracking.
Figure 66. Roll angle tracking during normal velocity tracking.
Aerospace 11 00079 g066
Figure 67. Pitch reference identification from tangential position kick maneuver.
Figure 67. Pitch reference identification from tangential position kick maneuver.
Aerospace 11 00079 g067
Figure 68. Model behavior in tangential position kick maneuver.
Figure 68. Model behavior in tangential position kick maneuver.
Aerospace 11 00079 g068
Figure 69. Position transients in tangential position kick maneuver.
Figure 69. Position transients in tangential position kick maneuver.
Aerospace 11 00079 g069
Figure 70. Velocity transients in tangential position kick maneuver.
Figure 70. Velocity transients in tangential position kick maneuver.
Aerospace 11 00079 g070
Figure 71. Pitch angle tracking in tangential position kick maneuver.
Figure 71. Pitch angle tracking in tangential position kick maneuver.
Aerospace 11 00079 g071
Table 1. Possible OSDK control mode settings.
Table 1. Possible OSDK control mode settings.
Logic IdentifierMode IdentifierExplanation
HorizontalCoordinateHORIZONTAL_GROUNDSet the x–y of ground frame as the horizontal frame (NEU)
HORIZONTAL_BODYSet the x–y of body frame as the horizontal frame (FRU)
HORIZONTAL_ANGLESet the control mode to control pitch and roll angle of the vehicle
HorizontalLogicHORIZONTAL_VELOCITYSet the control mode to control horizontal vehicle velocities
HORIZONTAL_POSITIONSet the control mode to control position offsets of pitch and roll directions
HORIZONTAL_ANGULAR_RATESet the control mode to control rate of change of the vehicle’s attitude
VerticalLogicVERTICAL_VELOCITYSet the control mode to control the vertical speed of UAV, upward is positive
VERTICAL_POSITIONSet the control mode to control the height of UAV
VERTICAL_THRUSTSet the control mode to directly control the thrust
YawLogicYAW_ANGLESet the control mode to control yaw angle
YAW_RATESet the control mode to control yaw angular velocity
Table 2. Mass of DJI M600 components for inertia calculations.
Table 2. Mass of DJI M600 components for inertia calculations.
IDNameMass (g)Element Count
1Motor3826
2Landing gear1052
3Folding arm466
4Battery590/6756
5Landing gear arm612
6Body26241
Table 3. Mass of payload components for inertia calculations.
Table 3. Mass of payload components for inertia calculations.
IDNameMass (g)Element Count
1GNIMU antenna1121
2GNIMU antenna stand531
3GNIMU1911
4Gimbal part 113.31
5Gimbal part 2241
6Gimbal part 3 (counter weight)1371
7Basler camera155.81
8Nvidia Jetson Xavier NX2161
9Base plate3251
10Gimbal motors1992
Table 4. Results of mass and inertia calculations.
Table 4. Results of mass and inertia calculations.
ConfigurationMass (g)Inertia Matrix (g·cm2)
Stock M600 with TB47S batteries9530 6.894 × 10 6 0 0 0 5.971 × 10 6 0 0 0 1.275 × 10 7
Stock M600 with TB48S batteries10,040 6.949 × 10 6 0 0 0 6.026 × 10 6 0 0 0 1.286 × 10 7
Payload M600 with TB47S batteries11,155 7.398 × 10 6 1375.236 8604.432 1375.236 6.524 × 10 6 1225.41 8604.432 1225.41 1.287 × 10 7
Payload M600 with TB48S batteries11,665 7.456 × 10 6 1376.109 8849.862 1376.109 6.582 × 10 6 1216.184 8849.862 1216.184 1.298 × 10 7
Table 5. Results of horizontal forces identification from FT1 flight campaign.
Table 5. Results of horizontal forces identification from FT1 flight campaign.
Parameter K hx K hy K x K y W T W N K ˜ y
Set FT1/10.71940.30960.05630.0314.46356.6090.0488
Set FT1/20.70280.2890.053904.6476100.0467
Average0.71110.29930.05510.01554.5558.30.04775
Table 6. Results of horizontal forces identification from the second flight campaign ( F T 2 ), first run. Outliers are denoted with bold face.
Table 6. Results of horizontal forces identification from the second flight campaign ( F T 2 ), first run. Outliers are denoted with bold face.
Parameter K hx K hy W N W E
Set FT2/11.10450.82652.4815–1.376
Set FT2/21.05270.92761.745–1.1056
Set FT2/31.0360.70771.613–0.67
Set FT2/41.1320.661.7222–1.2163
Average1.08130.82061.6934–1.2326
Table 7. Results of horizontal forces identification from the second flight campaign (FT2), second run. Outliers are denoted with boldface.
Table 7. Results of horizontal forces identification from the second flight campaign (FT2), second run. Outliers are denoted with boldface.
Parameter K x K y W N W E
Set FT2/10.10280.09682.57–1.41
Set FT2/20.09280.21811.747–1.12
Set FT2/30.09870.15821.581–0.57
Set FT2/40.10720.09341.667–1.28
Average0.10.09511.665–1.27
Table 8. Final results of horizontal forces identification from the second flight campaign (FT2). Outliers are denoted with boldface.
Table 8. Final results of horizontal forces identification from the second flight campaign (FT2). Outliers are denoted with boldface.
Parameter K hx K hy W N W E
Set FT2/10.96130.78812.41–1.325
Set FT2/20.9080.89511.668–1.1098
Set FT2/30.89660.67131.574–0.623
Set FT2/40.99110.61381.6592–1.2107
Average0.93920.78481.6337–1.2112
Table 9. Re-identified wind disturbances in the first flight campaign ( F T 1 ). Outliers are denoted with boldface.
Table 9. Re-identified wind disturbances in the first flight campaign ( F T 1 ). Outliers are denoted with boldface.
SetSubset W N W E
1–21–4.6152–0.4295
2–4.599–0.556
3–4.332–0.1331
4–4.5963–0.5295
Average–4.5356–0.505
31–5.2753–1.262
2–5.5744–0.8514
Average–5.4248–1.0576
Table 10. New fit of parameters in the second flight campaign ( F T 2 ) after air drag model refinement. Outliers are denoted with boldface.
Table 10. New fit of parameters in the second flight campaign ( F T 2 ) after air drag model refinement. Outliers are denoted with boldface.
Parameter K hx K hy W N W E
Set 10.99630.79542.4296–1.3371
Set 20.94330.9011.6879–1.0998
Set 30.93080.67861.5838–0.6343
Set 41.02560.67531.6592–1.2117
Average0.9740.79171.649–1.2162
Table 11. Hover thrust coefficients and engine speeds for m = 9.53 kg.
Table 11. Hover thrust coefficients and engine speeds for m = 9.53 kg.
FLY Nr.FT2/1FT2/2FT2/3FT2/4
c T 0 [-]0.01060.01020.01050.0101
Ω 0 [rad/s]275.8280.93277.08288.7
Table 12. Hover thrust coefficients and engine speeds for m = 10.04 kg.
Table 12. Hover thrust coefficients and engine speeds for m = 10.04 kg.
FLY Nr.FT1/1FT1/2FT1/3FT1/4FT2/1FT2/2FT2/3FT2/4FT2/5
c T 0 [-]0.01070.01060.01070.01060.01010.01030.01040.01070.0106
Ω 0 [rad/s]280.59282.54280.25282.74288.7286.17284.66280.57282.57
Table 13. Resulting vertical force coefficients and related V a z values from the first flight campaign ( F T 1 ).
Table 13. Resulting vertical force coefficients and related V a z values from the first flight campaign ( F T 1 ).
Maneuver K c V az [m/s]
Ascend1.7419–3.3
FAW 10 m/s2.5236–4
FAW 10 m/s1.7482–3.8
FAW 14 m/s3.4947–6
FAW 14 m/s4.5452–7
Ascend2.6345–3.5
Descend9.43852.8
Descend7.24952.7
Ascend2.1952–3.4
Table 14. Resulting vertical force coefficients and related V a z values from the second flight campaign ( F T 2 ).
Table 14. Resulting vertical force coefficients and related V a z values from the second flight campaign ( F T 2 ).
Maneuver K c V az [m/s]
Ascend3.5995–3.15
Ascend4.3–3.1
Descend2.8953
Ascend3.5535–3.1
Descend6.19132.9
Along 10 m/s–2.77–1.4
Diagonal 10 m/s–2.8–2.3
Cross 10 m/s–0.28–2
Along 14 m/s4.22–6
Cross 14 m/s2.79–4
Table 15. Quality measures for asymmetric and symmetric vertical force models.
Table 15. Quality measures for asymmetric and symmetric vertical force models.
FigureFigure 30Figure 31Figure 32
Asymmetric833.512162169
Symmetric675.814531623
Table 16. Pitch and roll moment parameters from first flight campaign ( F T 1 ).
Table 16. Pitch and roll moment parameters from first flight campaign ( F T 1 ).
Take-OffSet K Wq K Wp W
1Set FT1/1–2.3902–2.44444.5636
1Set FT1/2–2.3927–2.45374.5636
AVERAGE-–2.3914–2.4494.5636
2Set FT1/1–1.9803–2.0075.527
2Set FT1/2–2.0158–2.01365.527
AVERAGE-–1.9981–2.01035.527
Table 17. Pitch and roll moment parameters from second flight campaign ( F T 2 ).
Table 17. Pitch and roll moment parameters from second flight campaign ( F T 2 ).
Set K Wq K Wp W
Set FT2/1–5.2789–5.33292
Set FT2/2–5.216–5.17292
Set FT2/3–5.2445–5.26662
Set FT2/4–5.2464–5.22412
Set FT2/5–5.208–5.252
Set FT2/6–5.1866–5.17862
Set FT2/7–5.1939–5.0862
AVERAGE–5.2249–5.21592
Table 18. Yaw moment parameters.
Table 18. Yaw moment parameters.
FTSet K r c P 0
1Set 10.30350.2906
Set 20.30990.2961
Set 30.30920.2927
2Set 10.40640.2733
Set 20.3560.2552
Set 30.44030.2693
AVERAGE 0.35420.2795
Table 19. Vertical controller fit to flight data.
Table 19. Vertical controller fit to flight data.
FLYSetFit Quality
FT1158.08%
FT1258.13%
FT2343.33%
FT240.0627%
Table 20. Yaw controller transfer functions.
Table 20. Yaw controller transfer functions.
FLYSet G rE + G rE
FT11–3 G r E 1 + = 76.4 ( s + 0.43 ) s ( 0.046 s + 1 ) G r E 1 = 193.8544 ( s + 0.1243 ) s ( 0.6932 s + 1 )
FT12–4 G r E 2 + = 85.9512 s ( 0.0964 s + 1 ) G r E 2 = 77.4487 ( s + 0.5384 ) s ( 0.0134 s + 1 )
FT25–7 G r E 3 + = 68.43 ( s 0.1377 ) s ( 0.11 s + 1 ) G r E 3 = 76.8125 ( s + 0.4649 ) s ( 0.0653 s + 1 )
FT26–8 G r E 4 + = X s ( 0.0428 s + 1 ) G r E 4 = 67.3 ( s + 0.14 ) s ( 0.226 s + 1 )
Table 21. Data fit of final yaw controller transfer function.
Table 21. Data fit of final yaw controller transfer function.
FLYSet G rE + G rE
FT1125.16%24.13%
FT1245.37%29.25%
FT1342.01%33.01%
FT1469.72%51.36%
FT2542.63%70.45%
FT2652.07%64.4%
FT2743.78%62.7%
FT2848.59%50.13%
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

Bauer, P.; Nagy, M. Flight-Data-Based High-Fidelity System Identification of DJI M600 Pro Hexacopter. Aerospace 2024, 11, 79. https://doi.org/10.3390/aerospace11010079

AMA Style

Bauer P, Nagy M. Flight-Data-Based High-Fidelity System Identification of DJI M600 Pro Hexacopter. Aerospace. 2024; 11(1):79. https://doi.org/10.3390/aerospace11010079

Chicago/Turabian Style

Bauer, Péter, and Mihály Nagy. 2024. "Flight-Data-Based High-Fidelity System Identification of DJI M600 Pro Hexacopter" Aerospace 11, no. 1: 79. https://doi.org/10.3390/aerospace11010079

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