Content area

Abstract

This study investigates the tracking control of quadrotor micro aerial vehicles using nonlinear model predictive control (NMPC), with primary emphasis on the implementation of a real-time embedded control system. Apart from the limited memory size, one of the critical challenges is the limited processor speed on resource-constrained microcontroller units (MCUs). This technical issue becomes critical particularly when the maximum allowed computation time for real-time control exceeds 0.01 s, which is the typical sampling time required to ensure reliable control performance. To reduce the computational burden for NMPC, we first derive a nonlinear quadrotor model based on the quaternion number system rather than formulating nonlinear equations using conventional Euler angles. In addition, an implicit continuation generalized minimum residual optimization algorithm is designed for the fast computation of the optimal receding horizon control input. The proposed NMPC is extensively validated through rigorous simulations and experimental trials using Crazyflie 2.1®, an open-source flying development platform. Owing to the more precise prediction of the highly nonlinear quadrotor model, the proposed NMPC demonstrates that the tracking performance outperforms that of conventional linear MPCs. This study provides a basis and comprehensive guidelines for implementing the NMPC of nonlinear quadrotors on resource-constrained MCUs, with potential extensions to applications such as autonomous flight and obstacle avoidance.

Full text

Turn on search term navigation

1. Introduction

Quadrotor micro aerial vehicles (MAVs) are a type of unmanned aerial vehicle (UAV), also commonly referred to as drones or quadcopters, that use four rotors (propellers) to achieve lift and maneuverability. Because of their cost-effective structure, simple thrust system, and maneuverability for various applications, quadrotor MAVs have been rapidly developed as a new mobility platform. Currently, they are widely used in transportation, military weapons, surveillance, and other industrial applications. Among these applications, trajectory tracking control has received considerable attention as one of the most significant challenges. Unlike ground vehicles, aerial vehicles are more susceptible to external factors such as wind disturbances, owing to the inherent characteristics of flight. Reducing the mass of aerial systems extends their operational range and broadens their potential applications. However, unlike conventional mobility, MAVs must navigate various situations that arise during flight owing to the absence of pilots. Because quadrotors rely on a simple thrust mechanism based on four fixed rotors, the rotor speed is an exceptionally sensitive parameter that governs both position and attitude. When the torque constraints of the rotor are imposed, the ability of the quadrotor to track the desired trajectory is severely affected, posing critical operational challenges.

To date, proportional–integral–derivative (PID) control is the most common closed-loop control strategy for quadrotors owing to its simple control logic based on tracking error without the need for physical models. However, with input saturation, the inherent overshooting of the PID controller limits the tracking performance. To address these issues, many researchers have implemented more robust control methods, including backstepping control (BC) [1], sliding mode control [2], optimal control methods such as H control [3] and optimized BC techniques [4]. Nevertheless, the development of more stable and robust controllers for quadrotors remains challenging owing to physical constraints. Input saturation is often mitigated using methods such as the nested saturation method [5] and anti-windup scheme [6]. However, these approaches frequently result in suboptimal control performance.

Model predictive control (MPC) offers a compelling alternative for quadrotors with control input constraints because it systematically incorporates these constraints into the control process [7]. This systematic handling of constraints makes MPC applicable to fault-tolerant control [8] and path-tracking control with a more robust controller by including H control [9]. Although MPC demonstrates excellent potential for trajectory tracking under input saturation, its real-time implementation in quadrotor control remains uncertain owing to the computational burden of solving large matrix equations associated with highly nonlinear quadrotor dynamics over the receding horizon. Numerous studies have explored various explicit control approaches to address the computational burden of quadrotor dynamics. These include the use of a lookup table for explicit optimal control inputs [10,11], a classical method in quadrotor control applications, and techniques such as model reduction [12] to simplify computations or the use of neural networks [13] to enhance the trajectory tracking performance of explicit MPC. However, explicit methods that depend on look-up tables cannot ensure stability in many of the flight scenarios encountered during flight. To overcome these drawbacks, a wireless remote control was explored by integrating high-performance host PCs to ensure real-time control capability [14]. However, wireless remote control has several critical shortcomings hindering its practical application. Wireless systems are inherently vulnerable to jamming attacks and signal latency, which can deteriorate the stability and safety of aerial vehicles. For example, the signal latency in Bluetooth or similar low-power protocols typically ranges from 100 ms to 400 ms. These time delays require sophisticated time-delay compensation controller designs. Due to these technical limitations, there is a growing need to shift toward onboard embedded control architectures where control algorithms are executed directly on lightweight, low-power built-in microcontroller units (MCUs). However, tiny-sized MCUs offer a limited computational time and memory capacity (resource-constrained), which in turn poses significant challenges for implementing complex control algorithms such as nonlinear model predictive control (NMPC) for improving the tracking performance of quadrotors.

To reduce the computational burden for NMPC, most studies have focused on advancing optimization solvers, which includes quadratic programming (QP) [15], sequential quadratic programming (SQP) [16], real-time iteration (RTI) [17], and alternating direction method of multipliers (ADMM) [18]. The continuation/generalized minimal residual (C/GMRES) algorithm is a prominent method for NMPC in quadrotor systems [19]. C/GMRES enables the implicit fast computation of finite optimal horizon control input, as required in direct optimization approaches to solve the optimization problem. If the Jacobian of the cost function with respect to the control input is nonsingular, then the C/GMRES algorithm solves a single differential equation for the cost function instead of performing numerous iterations. The RTI and warm-started SQP methods require the explicit evaluation of sensitivities and matrix factorizations (e.g., for QP solving), which can be memory-intensive and introduce unpredictable computational latency on low-power MCUs. In contrast, the C/GMRES approach avoids matrix factorizations and permits flexible iteration control without requiring full convergence at every step, making it more suitable for resource-constrained platforms. Several strategies have been proposed to integrate C/GMRES into real-time control frameworks. For instance, a modified version of C/GMRES has been applied to AUV dynamics, resulting in improved tracking performance [20]. Combining C/GMRES with the autopilot systems of commercial low-cost quadrotors has resulted in enhanced tracking capabilities [21]. However, although C/GMRES optimization is more advantageous than other algorithms in terms of computation time, it still requires substantial computational resources due to the complexity of the nonlinear quadrotor model, making it challenging to implement in embedded real-time control systems.

While this study focuses on a model-based NMPC framework using the C/GMRES algorithm for efficient real-time control, it is worth noting that recent trends in control research have also explored model-free approaches. Techniques based on reinforcement learning and deep neural networks are actively being investigated for tasks such as system identification, adaptive control, and trajectory tracking in quadrotor systems. These data-driven methods are expected to complement model-based controllers and may offer future opportunities for hybrid or fully model-free embedded control architectures [22,23]. In parallel, recent developments in prescribed performance control have introduced low-complexity and singularity-free strategies, particularly for attitude stabilization in aerospace systems. These methods eliminate the need for online optimization or complex modeling, while ensuring robust performance even under actuator faults or uncertainties. Such lightweight Lyapunov-based approaches offer a promising alternative for embedded systems with severe computational constraints [24]. However, this may lead to a degraded performance when it fits an actual response variable outside the ranges; this is because most model-free deep learning models are fit to a response variable within a trained range. The extrapolation capability issues should be addressed.

Therefore, this study aims to implement a fast MPC framework using nonlinear quadrotor models by embedding the implicit C/GMRES algorithm into a tiny-sized resource-constrained MCUs. This study provides a basis and comprehensive guidelines for implementing the NMPC of nonlinear quadrotors on resource-constrained MCUs, with potential extensions to applications such as autonomous flight and obstacle avoidance. This study also addresses some technical challenges such as computational limitations and accuracy degradation in embedded control environments, particularly when the maximum computation time allowed e exceeds 0.01 s, which is the sampling time typically required to ensure reliable control performance. To the best of our knowledge, we report for the first time that it is possible to implement the embedded tracking control of quadrotors using NMPC with the C/GMRES optimization algorithm on a tiny-sized resource-constrained MCU. Section 2 outlines the quaternion-based nonlinear quadrotor model, and Section 3 details the C/GMRES optimization. Section 4 and Section 5 present the simulation and experimental validations, respectively, and Section 6 summarizes the main conclusions.

2. Dynamic Modeling of Quadrotor Systems

2.1. Quaternion-Based Nonlinear Quadrotor Model

In this study, an alternative modeling approach was employed to derive the full nonlinear governing equations for the motion of quadrotors based on the quaternion number system; this was rather than formulating nonlinear equations using conventional Euler angles-based dynamic models. The quadrotor is typically equipped with four rotors arranged in a cross-shaped configuration, MCUs, and secondary batteries, etc. [25], as shown in Figure 1. This system is typically classified as an under-actuated (non-holonomic) system because it has six degrees of freedom, whereas only four control inputs are available—namely, the normalized thrusts of the individual motors (u1,u2,u3 and u4).

These four control inputs determine the actual thrust force and rotor torques by using B-matrix (also called the input matrix or control distribution matrix), as follows:

(1)Fτxτyτz=KTΩmax2KTΩmax2KTΩmax2KTΩmax22lKTΩmax22lKTΩmax22lKTΩmax22lKTΩmax22lKTΩmax22lKTΩmax22lKTΩmax22lKTΩmax2KMΩmax2KMΩmax2KMΩmax2KMΩmax2u1u2u3u4

where KT and KM represent the constant thrust (lift) and moment (torque) coefficient (gains), depending on the rotor geometry. l denotes the distance from the center of mass of the quadrotor to the rotational axis of the two diagonally opposite rotors. Ωmax2 represents the squared maximum angular velocity. The net thrust force F in the vertical direction was directly proportional to the sum of the squared rotational speeds of all four rotors with a constant thrust coefficient. Two torques (roll τx, pitch τy) are directly proportional to the differences of thrust between the motors on the x- and y-axes, respectively, with a constant moment coefficient. The yaw torque (τz) was also proportional to the difference in torque between the clockwise and counterclockwise rotating rotors, which results in a torque that rotates the quadrotor around the vertical z axis. The thrust and three rotor torques are expressed as vectors in a body-fixed frame as follows;

(2)FB=0,0,FT,τB=τx,τy,τzT

The Euler–Newton equations for the quadrotor are then expressed as follows:

(3)FBτB=mI3×303×303×3Jcmv˙Rω˙B+03×1ωB×(JcmωB)

where vR=[vx,vy,vz]T and ωB=[ωx,ωy,ωz]T denote the linear and angular velocities of the quadrotor, respectively. Jcm is the moment of the inertia matrix about the center of mass, and is defined as follows:

(4)Jcm=JxxJxyJxzJxyJyyJyzJxzJyzJzz

In this study, we introduce an alternative approach based on quaternion mathematics to derive the full governing equations of quadrotors [26] because this system allowed more efficient implementation. The quadrotor system was then modeled with 13 state variables as follows:

(5)x=rRqvRωBT

where rR=[x,y,z]T denotes the position of the quadrotor and q=[q0,q1,q2,q3]T represents its attitude expressed using a unit quaternion (quaternion vector). When the angular velocity vector is in the body frame of reference, the derivative of the quaternion requires some algebraic manipulation and can be represented as follows [27]:

(6)q˙ωB(q,ωB)=120ωBq

The right-hand quaternion derivative from Equation (6) should be combined with the rotational dynamics from Equation (3), which results in a governing equation of motion describing the full rotational dynamics of the quadrotor in the quaternion form, as follows:

(7)q˙ωB(q,ωB)=120ωBqω˙B=J1cmτJ1cmωB×(JcmωB)

Consequently, the quadrotor model is represented by a hybrid frame and expressed in the form of a nonlinear state-space equation (details of the equation form are described in Appendix A).

(8)x˙=r˙Rq˙v˙Rω˙B=vR120ωBqg001+1mRqFBJcm1τBJcm1ωB×JcmωB

Because the quaternion vector q is constrained to lie on the unit hypersphere, it introduces redundancy in the state vector. To remove this redundancy and express the system in a minimal coordinate system, we project the nonlinear quaternion dynamics onto a local coordinate system using Rodrigues parameters, defined as follows [28]:

(9)ϕ=q1q2q3Tq0

The quadrotor system was then modeled with 12 state variables, as shown Equation (10), based on the Rodrigues parameter representation that eliminates the redundancy in quaternion-based dynamics.

(10)x=rRϕvRωBT

Compared to the conventional Euler angles-based model, the computational burden can be significantly reduced by up to 30% because quaternions require only four parameters (one scalar and a 3D vector), making them more memory-efficient than rotation matrices. In addition, quaternion operations such as rotation interpolation and composition are computationally more efficient than matrix operations; it is also unnecessary to compute sinusoidal functions in numerous rotating matrices, with these appearing in the Euler angles-based rigid-body dynamics.

2.2. Discretization

To design and implement a discrete NMPC for the simulation and real-time control experiment, the continuous dynamic model (i.e., Equation (8)) was discretized using the forward Euler difference method, as follows:

(11)x˙(t)=x(k+1)x(k)ΔT=f(x(k),u(k))

where ∆T is the time step (equivalent to the sampling time for discrete model predictive control). A time step of 0.01 s was selected after performing a comparison with the Runge–Kutta 4th-order method because the accuracy and stability of the Euler method typically depends on the step size, especially when choosing larger step sizes [18,25].

3. Nonlinear Model Predictive Control

3.1. Classical Nonlinear Model Predictive Control

The conventional NMPC uses a control algorithm with a nonlinear dynamic model to calculate the optimal control input, which is in turn the initial value of the control inputs within a specified receding horizon. NMPC has a high computational cost owing to the iterative computation of large matrices associated with optimization algorithms (typically quadratic programming, QP) [29]. The optimization problem can be formulated with the following cost function, subject to the constraints [30]:

(12)minuiJ=i=0N1L(xi,ui)ΔT+φ(xN)s.t.xi+1=xi+f(xi,ui)ΔTx=x(t0).

The continuous-time system x˙=f(x,u), which serves as an equality constraint, was discretized using the forward Euler difference method, and the initial condition for the prediction model was provided by the current measured state x(t0). The control inputs were bounded within the normalized range of [0, 1] to consider the actuation limits (inequality constraint).

(13)x0=x(t0)0ui1,fori=1,2,3,4

3.2. C/GMRES Optimization

In this study, the implicit (on-line) C/GMRES optimization algorithm was designed for the fast computation of the optimal receding horizon control input, as shown in Figure 2 [19,20,31]. This algorithm was tailored to solve the NMPC with the necessary conditions for optimal control. To this end, the Hamiltonian is expressed as follows:

(14)H(x,λ,u)=L(x,u)+λTf(x,u)

where λ is the Lagrange multiplier (costate variable) for equality constraint. The discretized optimal control equations require that for local optimal control, {ui*}i=0N1 and {λi*}i=0N1 satisfy the following conditions:

(15)xi+1*=xi*+f(xi*,ui*)ΔTλi=λi+1+HxT(xi*,λi+1*,ui*)ΔTλN=φxT(xN*)x0*=x(t0)

(16)Hu(xi*,λi+1*,ui*)=0

The asterisk (*) denotes the optimal value obtained through optimization. Equation (15) is a recurrence relationship involving x* and λ*, along with the boundary condition.

The control input U is then defined as

(17)U=col(u0*,u1*,,uN1*)

The sequences of {xi*}i=0N {λi*}i=0N are explicit functions of U. Substituting Equation (15) into Equation (16) yields

(18)F(U,x)=HuT(x0*,λ1*,u0*)HuT(x1*,λ2*,u1*)HuT(xN1*,λN*,uN1*)=0

Consequently, the optimality conditions in Equation (16) can be formulated as a system of equations with dimension nuN, where nu denotes the number of control inputs and N the number of prediction steps.

In fact, the inequality constraints on control inputs should be incorporated into the cost function (Equation (14)) using the second Lagrangian multiplier (hard constraints). The solution must then satisfy additional necessary conditions known as Karush–Kuhn–Tucker conditions for optimality, which requires the computation of additional Jacobians and Hessians of the Lagrangian function. This process becomes computationally intensive for high-dimensional systems. In particular, such computational burdens can be critical in real-time applications such as NMPC, where a highly nonlinear dynamic model is used to predict optimal outputs. Furthermore, if the constraints are infeasible (e.g., due to disturbances or model uncertainty), the optimization problem has no solution, leading to control failure. In this study, the penalty term for soft constraints was then designed to alleviate the computational burden in an efficient manner. The original cost function is then augmented as follows;

(19)H(x,λ,u,ρ)=L(x,u)+λTf(x,u)+α2u+yproj(u+y)2

where α denotes a penalty parameter that scales the penalty applied to constraint violations. Equation (18) is accordingly modified as follows:

(20)F(U,x)=HuT(x0*,λ1*,u0*)+α(u0*z0*+y0*)HuT(x1*,λ2*,u1*)+α(u1*z1*+y1*)HuT(xN1*,λN*,uN1*)+α(uN1*zN1*+yN1*)=0

The variable zk refers to the projection of the input onto the feasible sets, typically through clipping, to satisfy input bounds.

(21)zk=proju(uk+yk)=min(max(uk+yk,umin),umax)

The dual variable yk serves a role analogous to a Lagrange multiplier. It is updated at each iteration to reinforce the constraint satisfaction by adjusting the penalty term accordingly.

(22)ykyk+ukzk

The inequality constraints on the control inputs are handled using this soft constraint formulation, which allows for some degree of constraint violation during control actions. A penalty term can guide the control input into the feasible set via projection. This simplified approach allows the proposed fast NMPC to be a practical solution for real-time control. The penalty parameter was tuned as 100, considering the normalized range of control inputs.

Finally, Equation (20) must be solved for each sampling time. In the C/GMRES algorithm, a first-order differential equation is introduced to solve a system of equations, as follows:

(23)F˙(U,x,t)=FUU˙+Fxx˙+Ftt˙=MF(U,x,t)

where M is a stable positive definite matrix that stabilizes F(U,x)=0. If the Jacobian FU is invertible (i.e., nonsingular), the differential equation yields the following equation:

(24)U˙=FU1(MFFxx˙Ft)

In addition, the three Jacobians (Fx,FU and Ft) are obtained using forward difference approximations as follows:

(25)FUU,x,tW+FxU,x,tw+FtU,x,tω1hFU+hW,x+hw,t+hωFU,x,t

where h is a small positive parameter. Thus, C/GMRES was intended to solve the Equation (24) to avoid a computational burden for matrix inversion. The combination of forward difference approximation and GMRES is referred to as FDGMRES [17].

(26)U˙=FDGMRES(U,x,x˙,t,U˙^,h,kmax)

where U˙^ is the initial guess and kmax is the maximum number of iterations. The transformation T0(U)=us defines the process of selecting the optimal control input us from the optimization variable U, which is then applied as the system control input, as shown in Algorithm 1.
Algorithm 1. Forward Difference GMRES(FDGMRES)
1: r^:=b(U,x,x˙,t)DhF(U,x+hx˙,t+h:U˙^,0,0),v1:=r^/r^,ρ:=r^,β:=ρ,k:=0.
2: Whilek<kmax,do
3:    k:=k+1
4:    vk+1:=DhF(U,x+hx˙,t+h:vk,0,0)
5:       forj=1,,k
6:       hjk:=vk+1Tvj
7:       vk+1:=vk+1hjkvj
8:    hk+1,k:=vk+1

4. Simulation Results

The discretized nonlinear quadrotor model (Equation (11)), controlled by NMPC with C/GMRES optimization, was simulated to evaluate the tracking control performance of the NMPC. The model parameters for simulation are listed in Table 1. All results related to the C/GMRES algorithm were obtained using a maximum Krylov subspace dimension of kmax=4 and stable matrix M=ζI with ζ=1/2Δt. A discrete solver (∆T = 0.01 s) was used primarily to solve the highly nonlinear discrete quadrotor model. It computes the next simulation time step for a model and updates its individual discrete states. Three flying scenarios (step, ∞-shaped, and sinusoidal transition reference trajectory) were simulated. All integrated simulation scripts were coded in C language, considering real-time embedded control, and it was executed in a Linux environment (Lenovo Group Ltd., Beijing, China; CPU: AMD Ryzen™ 7 5800H with Radeon™ Graphics, 3.20 GHz, and NVIDIA GeForce RTX 3070 Laptop GPU). Compared to the nonlinear quadrotor model based on conventional Euler rotation angles, the quadrotor model based on quaternion mathematics was more efficient, reducing the computation time by up to 30%. To validate the computational efficiency of C/GMRES, we performed a benchmark comparing the performance of C/GMRES and a standard MPC solver using sequential quadratic programming (SQP), under identical settings such as prediction horizon, model dynamics, and solver tolerances. The C/GMRES solver achieved approximately ten times faster computation per optimization step, confirming its efficiency in the tested scenarios. A linear MPC (LMPC) with a linearized model (summarized in Appendix B) was also compared with NMPC. The baseline prediction and control horizon size (N) was set to 5, considering both the computation time and prediction accuracy. To evaluate the transient tracking performance and quantitative metrics, the root mean square error (RMSE) was calculated and the mean of the RMSE (MRMSE) was evaluated; these were finally averaged with three values corresponding to three axes.

(27)RMSE=1nk=1nxr(k)x(k)2

where xr(k) and x(k) are the reference and controlled output response, respectively.

The step reference trajectory (path) was used for the free flight of a quadrotor controlled by the NMPC. The step reference trajectory comprises a step change in the x, y, and z-directions, where the target position transitions from (0, 0, 0.5) to (0.5, 0.5, 1) at the 2 s mark, followed by a stationary period at the target position. The flight velocity of the quadrotor for simulation was calculated approximately as 0.6 m/s.

(28)xr(t),yr(t)=0,0t20.5,t>2,zr(t)=0.5,0t21,t>2

The different sampling times were used to examine the effect of sampling time, maintaining the same prediction horizon time (∆T·N = 0.1 s). As a result, the prediction horizon size (N) was 10 for ∆T = 0.01 s and the prediction horizon size (N) was 5 for ∆T = 0.02 s. The control responses to a step reference trajectory for different sampling times are compared in Figure 3. The control inputs corresponding to NMPC (∆T = 0.01 s) are illustrated in Figure 3e–h. The simulation results indicated that the proposed NMPC exhibited a faster response time (peak time of 0.1 s) with acceptable overshoot and small tracking errors (MRMSE = 0.0175) in comparison to LMPC (MRMSE = 0.0196). NMPC with a sampling time of ∆T = 0.01 s exhibited faster transient control responses. As expected, the normalized thrust control input (Figure 3h) was clipped to its maximum limited value owing to the constraints of NMPC (i.e., actuation limit, 0ui1, for i=1,2,3,4).

The different prediction horizon size (N) was used to examine the effect of the prediction horizon size, maintaining the same sampling time (0.01 s). The control responses to a step reference trajectory for different prediction horizon sizes are compared in Figure 4. The simulation results indicated that the proposed NMPC exhibited a faster response time with small tracking errors (MRMSE = 0.0198), in comparison to LMPC (MRMSE = 0.0421). NMPC with a larger prediction horizon size (N = 10) exhibited improved transient control responses. It is also evident that the tracking performance of NMPC outperforms that of LMPC, particularly in the z-direction. While a larger horizon generally improves tracking accuracy, the simulation results demonstrate that, with the appropriate tuning of the Q and R matrices, even a shorter horizon can yield a comparable performance. These results indicate that a shorter prediction horizon can offer a favorable trade-off between computational efficiency and control performance.

The robustness of the proposed NMPC against parametric model uncertainty was analyzed by introducing the perturbation of the thrust coefficient and quadrotor mass. Because the thrust coefficient is typically experimentally determined by system identification and can be inherently associated with open-loop motor control, the effect of thrust coefficient uncertainty on the tracking control performance was examined. The nominal thrust coefficient (0.25×106 in Table 1) was then perturbed by −5% (0.2375×106) and +5% (0.2625×106). The quadrotor mass was also one of the significant parametric uncertainties because the quadrotor mass can vary by payloads when the quadrotor is used for delivery purposes. The nominal quadrotor mass (0.033 kg) was also perturbed by −5% (0.03135 kg) and +5% (0.03465 kg). The relative error to the nominal performance (i.e., the normalized performance measure) was quantitatively evaluated.

(29)Relative Error=MRMSEPerturbedMRMSENominalMRMSENominal

While the relative errors in the x and y-axis were negligible (approximately 0.01), a significant error of 6 was observed in the vertical z-axis. The vertical z-position was found to be highly sensitive to variations in the thrust coefficient and mass, as shown in Figure 5b,d. Nonlinear model-based NMPC seems to be not robust against some parametric uncertainty, such as the thrust coefficient and mass. Such limitations can be addressed by utilizing more advanced MPC, such as the adaptive MPC for estimating critical model parameters online.

In MPC, the cost function essentially quantifies the difference (future error) between the predicted output from a model and the desired reference, as defined in Equation (12) and Figure 2. Since the goal is to find the optimal control inputs that minimize this cost function, a convergence analysis was then performed to confirm the optimality of the C/GMRES optimization algorithms. As shown in Figure 6, the cost function histories of the C/GMRES algorithm for all cases converged to a constant (flat) after 100 iterations, and a shorter sampling time resulted in a greater number of iterations converging. These results indicated that the cost function was rapidly minimized by the C/GMRES optimization algorithm.

The path tracking control performance was further evaluated with aggressive reference trajectories, including an ∞-shaped path and a sinusoidal transition trajectory, as shown in Figure 7 and Figure 8. While the ∞-shaped trajectory consists of multiple waypoints and is smoothly interpolated using spline curves for minimum snapping, the sinusoidal reference trajectory was synthesized by using three equations, as follows:

(30)xr(t)=xR(t)=0.3cos(210πt)yR(t)=0.3sin(210πt)cos(210πt)zR(t)=0.3cos(210πt)+0.5

The proposed NMPC successfully tracked the ∞-shaped reference trajectory with the yaw angle reference input and the polynomial transient trajectory after a short period of hovering. The NMPC achieved an improved tracking error (∞-shaped: MRMSE = 0.2351 for NMPC and MRMSE = 0.2442 for LMPC, sinusoidal: MRMSE = 0.0389 for NMPC and MRMSE = 0.0.0592 for LMPC). An increase in tracking error was observed when the yaw angle reference input was introduced. The aggressiveness of a reference trajectory can be partly quantified by the curvature of the path, as a higher curvature generally indicates sharper turns and more challenging tracking conditions. Despite the more aggressive trajectory (higher curvature of Figure 8), the tracking control performance remained unaffected.

5. Embedded Control Experiment

5.1. Experimental Set-Up

The real-time control capability of the proposed NMPC was evaluated using a tiny-sized quadrotor development platform (Crazyflie 2.1®, Bitcraze AB, Malmö, Sweden), as shown in Figure 9 [33,34,35]. The primary MCU is an ARM Cortex-M4 (STM32F405) clocked at 168 MHz with 192 kB SRAM and 1 MB flash capacities. The sampling time for the experiment was determined to be 0.01 s (100 Hz) after analyzing the simulated tracking performance evaluated in Section 5. Thus, the computation time per every sampling period should not exceed 0.01 s on current resource-constrained MCUs. In addition, although the optimality can be improved with a larger prediction horizon size, the receding horizon size was determined to be 5 in the experiment, as real-time capabilities could not be guaranteed for N > 7 on the current MCU.

For the rapid prototyping and indoor localization of quadrotors, the location of the flying quadrotor was measured using an optical localization system (Bitcraze Lighthouse® [36,37]). As shown in Figure 9b, two base stations remotely transmitted the measured position data to the quadrotor with an add-on shield board (Lighthouse deck) capable of receiving IR signals from base stations that can transmit the measured positioning data at a sampling frequency of 50 Hz using built-in infrared sensors. For real outdoor applications, other localization methods, such as the global positioning system, can be employed. The built-in inertial measurement unit (IMU, model: BMI088) provides three-axis accelerometer and gyroscope measurements, which are used for real-time motion prediction, while the Lighthouse data is used to correct accumulated drift. The all-state variables were obtained from the measurements of IMU (100 Hz) by using an extended Kalman filter (EKF) embedded in a firmware. Then, Lighthouse data (50 Hz) allowed the quadrotor to continuously update their most likely position. The optimal control input moves were then modulated into pulse width modulation (PWM) signals for DC motor control (open-loop control). A compact lithium polymer battery (250 mAh) served as the power source for the quadrotor and add-on shield board (Lighthouse deck). The estimated states and reference trajectories were communicated remotely using a wireless transceiver module (Crazyradio 2.1®) equipped with a system-on-a-chip (model: nRF52840) designed for low-latency communication (10–100 ms), enabling the minimization of delays that could affect the real-time control performance. All integrated scripts for the experiment were then built into firmware and downloaded to the quadrotor for real-time embedded control [38]. Before the flight, the battery was fully charged to deliver sufficient power and propeller was balanced because imbalanced propellers can lead to vibrations and noise in the sensors.

5.2. Parameter Identification

Based on the robustness analysis (Figure 5), the parameter identification was performed to estimate the key model parameters, as NMPC relies on an accurate prediction model. The accuracy of the prediction model can be determined by the prediction error, which refers to the difference between the actual measured output and the predicted output at the previous time step. Only the first move of the previous predicted output in the receding horizon was applied to compute the prediction error.

(31)e(k+1)=x(k+1)x^(kk)

Prediction errors can arise due to inaccurate control allocation, disturbances, or parametric uncertainty. In practice, the computed control input should be properly allocated and be the same as the actual control inputs. If electric DC motors (actuators) malfunction typically, caused by the open-loop PWM control, the allocated rotational speeds (eventually thrust and torques) are no longer identical to the actual rotational speed. Two key model parameters (thrust and moment coefficient in B-matrix) are then selected for the identified parameters. However, the online parameter identification of closed-loop control systems is challenging. Moreover, open-loop control responses for system identification methods, such as the recursive least square estimator, are not available because the quadrotor model is originally unstable. In this initial preliminary study, two key model parameters for the prediction model shown in Table 1 are optimally tuned with the experimental prediction error histories for two state variables out of 12 state variables, as illustrated in Figure 10. Prediction errors were primarily observed during hovering. The experimentally identified model parameters are listed in Table 2, reducing the MRMSE from 0.002 to 0.0008.

5.3. Tracking Control Performance

In this study, to evaluate the tracking control performance, four control cases were compared: Case A (unconstrained linear quadratic regulator (LQR) control), Case B (ADMM optimization [33]), Case C (proposed C/GMRES optimization), and Case D (QP). For Case A, the optimal feedback gain matrix was calculated offline and presented in Appendix B. The experimental control responses for the free flight test to step reference are compared in Figure 11. Their main features and tracking control performances are summarized and compared in Table 3. The average elapsed (computation) time was measured using the data watch-point and trace cycle counter of the ARM Cortex-M4 on the STM32F405 microcontroller. The number of clock cycles per MPC iteration was recorded and converted into milliseconds using the 168 MHz system clock. The memory usage was measured by analyzing the compiled executable and linkable format binary using the arm-none-eabi-size tool, which reports the sizes of memory sections. The sampling time was set to 0.01 s, and the prediction horizon size was set to 5 for Case B and C because none of the cases support real-time computation due to memory limitations when the prediction horizon is set to 7 or higher. The experimental results for Case C showed good agreement with the simulation results shown in Figure 3 and Figure 4. As expected, the average time elapsed on the current resource-constrained MCU was estimated to be lower than the sampling time, indicating feasibility for real-time operation. Similar to the simulation results, it exhibited the best transient response, with acceptable overshoot and response times and small tracking errors. The conventional QP optimization algorithm (Case D) does not allow real-time computation due to the lack of memory usage on the current resource-constrained MCU. The average elapsed time and memory usage on the MCU for QP were then estimated from the simulation results. In addition, the memory requirement for Case C was nearly the same as that for Case B even though Case C employs a nonlinear model to predict the future outputs.

The robustness of the proposed NMPC against parametric uncertainty was briefly analyzed by introducing the perturbation of main parameters. The nominal thrust coefficient (KT=0.27×106) was perturbed by −5% (0.2375×106) and +5% (0.2625×106) based on Section 5.2. As shown in Figure 12, the only z-position was sensitive to the KT uncertainty and showed good agreement with the simulation shown in Figure 5. Although two primary model parameters (thrust and moment coefficients) were optimally tuned, it was still necessary to further compensate for the prediction error, as they are time-varying and subject to disturbance. Such errors can lead to suboptimal control actions, resulting in slower responses, higher overshoot, or even instability.

The two aggressive reference trajectories (∞-shaped and sinusoidal transition same as simulation) were also used to further evaluate the robustness and tracking performance, as shown in Figure 13. The results showed good agreement with the simulations in terms of tracking error. The results also revealed that Case C efficiently solved the NMPC problem while maintaining an acceptable tracking performance compared to the other cases, supporting its suitability for embedded applications. Although the proposed NMPC showed a good average tracking performance, some technical limitations were observed. For example, the non-holonomic nature of quadrotors contributed to a degraded tracking performance during ∞-shaped trajectory tracking, where additional yaw motion tracking was required. This limitation can be addressed by increasing the prediction horizon size with high-performance MCUs. In addition, the technical issue of occasional localization errors (e.g., spurious spikes in position), caused by intermittent connection losses or occlusions from the cost-effective commercial Lighthouse system, needs to be addressed. The inaccurate control allocation also needs to be enhanced. In practice, the computed control input can be more effectively allocated through the closed-loop motor control, a method currently implemented in high-end quadrotor platforms.

6. Conclusions

In this study, we successfully implemented the embedded tracking control of quadrotors using NMPC with the implicit C/GMRES algorithm. The main contributions of this study are summarized as follows.

(1). First, we conclude that it is possible to efficiently implement NMPC for nonlinear quadrotor control on resource-constrained MCUs such as ARM Cortex-M4, particularly when the maximum allowed computation time is expected to exceed the required sampling time (∆T = 0.01 s), ensuring reliable control performance. Owing to the implicit C/GMRES algorithm, combined with the penalty term for soft constraint, the proposed NMPC offers a promising and efficient solution that significantly reduces the computation burden while keeping the loss of optimality to a minimum. This approach leverages C/GMRES optimization for the embedded real-time control of quadrotors.

(2). Secondly, an advantage of using the nonlinear quadrotor model based on the quaternion number system, rather than conventional Euler rotation angles, is its higher efficiency, as a simulation-based benchmark showed that the quaternion model reduced the computation time by 30% in the same PC, based on 100 repeated state predictions under identical input conditions. The computation time largely depends on the prediction model, as NMPC uses a nonlinear quadrotor model to predict optimal outputs over the prediction horizon.

(3). Lastly, this study provides a basis and comprehensive guidelines for implementing the NMPC of nonlinear quadrotors on resource-constrained MCUs, with potential extensions to applications such as autonomous flight and obstacle avoidance. For instance, the effects of the prediction horizon time and the uncertainty of two coefficients (thrust and moment), along with parameter identification, were analyzed and discussed in both simulations and experiments. To enable the further embedding of algorithms such as local path planning on resource-constrained MCUs, the computational resources required for low-level path tracking control (NMPC) should be minimized as much as possible.

However, it is still necessary to ensure the stability and robustness of the proposed algorithm against parametric uncertainties such as the thrust coefficient. In future investigations, we will continue to address some ongoing issues, such as the online parameter identification of closed-loop control systems (i.e., NMPC). We will also focus on advancing the embedded control capabilities on more resource-constrained MCUs (e.g., limited memory size). Some challenges still remain and could be addressed by designing more advanced optimization algorithms, even though this initial study demonstrated that NMPC with the C/GMRES optimization solver is a promising solution for the NMPC of quadrotors.

Author Contributions

G.-W.K. takes primary responsibility for this research as the principal investigator and drafted the manuscript. D.-M.L. contributed to the analysis, algorithm, and writing of the manuscript. Y.-S.S. and J.-H.J. contributed to the experimental work. All authors have read and agreed to the published version of the manuscript.

Data Availability Statement

Data are contained within the article.

Acknowledgments

The authors would like to thank Ji-Hoon Choi for their assistance with the experiment.

Conflicts of Interest

The authors declare no conflicts of interest.

Footnotes

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.

Figures and Tables

Figure 1 Quadrotor states represented in inertial and body-fixed coordinate system.

View Image -

Figure 2 Control block diagram for the tracking control of quadrotors using NMPC.

View Image -

Figure 3 Simulated tracking control responses to a step reference trajectory (Q = diag [3000 3000 1000 200 200 1000 45 45 60 6 6 10], R = diag [500 500 500 500]) for different sampling times: (a) x-position, (b) y-position, (c) z-position, (d) yaw attitude, and control inputs corresponding to NMPC (∆T = 0.01 s, N = 5) (e) F, (f) τx, (g) τy, and (h) normalized thrust forces.

View Image -

Figure 4 Simulated tracking control responses to a step reference trajectory (Q = diag [14,000 14,000 900 70 70 2000 90 90 45 3 3 10], R = diag [500 500 500 500]) for different horizon sizes: (a) x-position, (b) y-position, (c) z-position, (d) yaw attitude.

View Image -

Figure 5 Simulated tacking control responses to a step reference trajectory (Q = diag [14,000 14,000 900 70 70 2000 45 45 60 3 3 10], R = diag [500 500 500 500]) for (a,b) thrust coefficient KT uncertainty, and (c,d) quadrotor mass uncertainty.

View Image -

Figure 6 Convergence histories of C/GMRES optimization for different sampling times and prediction horizon sizes.

View Image -

Figure 7 Simulated tracking control responses to the ∞-shaped reference trajectory (Q = diag [15,000 15,000 3000 120 120 2000 120 120 120 5 5 10], R = diag [100 100 100 100]): (a) 3D plane; (b) x-y plane.

View Image -

Figure 8 Simulated tracking control responses to the sinusoidal transition reference trajectory (Q = diag [15,000 15,000 3000 120 120 2000 120 120 120 5 5 10], R = diag [100 100 100 100]): (a) 3D plane; (b) z-y plane.

View Image -

Figure 9 Experimental set-up. (a) Crazyflie 2.1, (b) optical localization system consisting of two base stations, and (c) block diagram.

View Image -

Figure 10 Time history of prediction error (v0 = 0.6 m/s, ∆T = 0.01 s, N = 5), Q = diag [14,000 14,000 900 70 70 2000 45 45 45 3 3 10], R = diag [500 500 500 500]): (a) before being tuned and (b) after being tuned.

View Image -

Figure 11 Experimental tracking control responses of the free flight test to step reference (Q = diag [10,000 10,000 1000 70 70 3000 60 60 20 5 5 10], R = diag [100 100 100 100]): (a) x-position, (b) y-position, (c) z-position, (d) yaw attitude.

View Image -

Figure 12 Experimental tracking control responses of the free flight test to step reference for quadrotor parameter (thrust coefficient) uncertainty (Case C, Q = diag [10,000 10,000 1000 70 70 3000 60 60 25 5 5 10], R = diag [100 100 100 100]): (a) x-position, (b) y-position, (c) z-position, (d) yaw attitude.

View Image -

Figure 13 Experimental tracking control responses (3-D plane, Q = diag [15,000 15,000 3000 150 150 3000 120 120 120 10 10 10], R = diag [100 100 100 100]): (a) to ∞-shaped reference (Video S1) (b) to sinusoidal transition reference.

View Image -

Model parameters and coefficients for the simulation of the quadrotor system [32].

Symbol Parameters Value
K T Thrust coefficient 0.25 × 10 6 kg · m / rad 2
K M Moment coefficient 0.2 × 10 9   kg m 2 / rad 2
Ωmax Maximum rotational speed 5869.0   rad / s
l Arm length 0.046   m
m Mass of quadrotor 0.033   kg
Jxx, Jyy Moment of inertia (x- and y-axis) 1.66 × 10 5   kg m 2
Jzz Moment of inertia (z-axis) 2.93 × 10 5   kg m 2
Jxy Moment of inertia (xy-plane) 0.83 × 10 6   kg m 2
Jxz Moment of inertia (xz-plane) 0.72 × 10 6   kg m 2
Jyz Moment of inertia (yz-axis) 1.8 × 10 6   kg m 2

Experimentally identified parameters for prediction model.

Symbol Parameters Value
K T Thrust coefficient 0.27 × 10 6 kg m / rad 2
K M Moment coefficient 0.16 × 10 8 kg m 2 / rad 2

Quantitative comparison of Figure 11 and qualitative comparison of four cases.

Index A (LQR) B C (Proposed) D
Optimization solver - ADMM C/GMRES QP
Prediction model - Linear Nonlinear Linear
MRMSE 0.0365 0.0292 0.0165 0.0081 (simulated)
Average elapsed time (ms) 0.07 0.9 2.3 0.8 (estimated)
Sampling time (s) 0.01 0.01 0.01 0.01
Average memory (kB) 124.1 127.07 130.05 200 (estimated)

Supplementary Materials

The following supporting information can be downloaded at: https://www.mdpi.com/article/10.3390/electronics14142775/s1. Video S1: Tracking Control of Quadrotor Micro Aerial Vehicles Using Efficient Nonlinear Model Predictive Control with C/GMRES Optimization on Resource-Constrained Microcontrollers.

Appendix A

Equation form of quaternion-based nonlinear quadrotor model.x˙=vx,y˙=vy,z˙=vzq˙0=12(ωxq1+ωyq2+ωzq3)q˙1=12(ωxq0+ωzq2ωyq3)q˙2=12(ωyq0ωzq1+ωxq3)q˙3=12(ωzq0+ωyq1ωxq2)v˙x=2KT(q0q2+q1q3)m(q02+q12+q22+q32)(u1+u2+u3+u4)v˙y=2KT(q0q1q2q3)m(q02+q12+q22+q32)(u1+u2+u3+u4)v˙z=KT(u1+u2+u3+u4)(q02q12q22+q32)mg(q02+q12+q22+q32)m(q02+q12+q22+q32)ω˙x=(JxyJyzJxzJyy)τz(JxyJzzJxzJyz)τy(JyyJzzJyz2)τxJxxJxxJxx+JxxJyz2+Jxy2Jxx2JxxJxxJxx+Jxz2Jxxω˙y=(JxxJyzJxyJxz)τz+(JxxJzzJxz2)τy+(JxyJzzJxzJyz)τxJxxJxxJxx+JxxJyz2+Jxy2Jxx2JxxJxxJxx+Jxz2Jxxω˙z=(JxxJyyJxy2)τz(JxxJyzJxyJxz)τy(JxyJyzJxzJyy)τxJxxJxxJxx+JxxJyz2+Jxy2Jxx2JxxJxxJxx+Jxz2Jxx

Appendix B

Equilibrium point xo=x0y0z01000000000T.

Linearized model at equilibrium point.Ac=000000010000000000000100000000000001000000000000000000000000000.500000000000000.500000000000000.50000019.610000000000019.61000000000000000000000000000000000000000000000000000000000000x=x0

Feedback gain matrix for LQR control.K=0.1820.1790.2380.5560.1790.1710.2380.4750.1690.1740.2380.4920.1670.1760.2380.540.6060.7610.110.1060.590.7740.1080.0980.4450.8060.0960.10.4290.7930.0930.1040.1560.0420.0510.2480.1560.0280.050.2470.1560.030.0210.2440.1560.040.0190.245

References

1. Rodríguez-Abreo, O.; Garcia-Guendulain, J.M.; Hernández-Alvarado, R.; Rangel, A.F.; Fuentes-Silva, C. Genetic Algorithm-Based Tuning of Backstepping Controller for a Quadrotor-Type Unmanned Aerial Vehicle. Electronics; 2020; 9, 1735. [DOI: https://dx.doi.org/10.3390/electronics9101735]

2. Al-Dhaifallah, M.; Al-Qahtani, F.M.; Elferik, S.; Saif, A.-W.A. Quadrotor Robust Fractional-Order Sliding Mode Control in Unmanned Aerial Vehicles for Eliminating External Disturbances. Aerospace; 2023; 10, 665. [DOI: https://dx.doi.org/10.3390/aerospace10080665]

3. Raffo, G.V.; Ortega, M.G.; Rubio, F.R. An integral predictive/nonlinear H∞ control structure for a quadrotor helicopter. Automatica; 2010; 46, pp. 29-39. [DOI: https://dx.doi.org/10.1016/j.automatica.2009.10.018]

4. Wen, G.; Ge, S.S.; Chen, C.L.P.; Tu, F.; Wang, S. Adaptive Tracking Control of Surface Vessel Using Optimized Backstepping Technique. IEEE Trans. Cybern.; 2018; 49, pp. 3420-3431. [DOI: https://dx.doi.org/10.1109/TCYB.2018.2844177]

5. Zhang, X.; Li, H.; Zhu, G.; Zhang, Y.; Wang, C.; Wang, Y.; Su, C.-Y. Finite-Time Adaptive Quantized Control for Quadrotor Aerial Vehicle with Full States Constraints and Validation on QDrone Experimental Platform. Drones; 2024; 8, 264. [DOI: https://dx.doi.org/10.3390/drones8060264]

6. Li, S.; Wang, Y.; Tan, J. Adaptive and robust control of quadrotor aircrafts with input saturation. Nonlinear Dyn.; 2017; 89, pp. 255-265. [DOI: https://dx.doi.org/10.1007/s11071-017-3451-z]

7. Merabti, H.; Bouchachi, I.; Belarbi, K. Nonlinear Model Predictive Control of Quadcopter. Proceedings of the 2015 16th International Conference on Sciences and Techniques of Automatic Control and Computer Engineering (STA); Monastir, Tunisia, 21–23 December 2015; IEEE: Piscataway, NJ, USA, 2015.

8. Nan, F.; Sun, S.; Foehn, P.; Scaramuzza, D. Nonlinear MPC for Quadrotor Fault-Tolerant Control. IEEE Robot. Autom. Lett.; 2022; 7, pp. 5047-5054. [DOI: https://dx.doi.org/10.1109/LRA.2022.3154033]

9. Raffo, G.V.; Ortega, M.G.; Rubio, F.R. MPC with nonlinear ℋ∞ control for path tracking of a quad-rotor helicopter. IFAC Proc. Vol.; 2008; 41, pp. 8564-8569. [DOI: https://dx.doi.org/10.3182/20080706-5-KR-1001.01448]

10. Liu, C.; Lu, H.; Chen, W.-H. An Explicit MPC for Quadrotor Trajectory Tracking. Proceedings of the 2015 34th Chinese Control Conference (CCC); Hangzhou, China, 28–30 July 2015; IEEE: Piscataway, NJ, USA, 2015.

11. Wang, Y.; Boyd, S. Fast Model Predictive Control Using Online Optimization. IEEE Trans. Control. Syst. Technol.; 2009; 18, pp. 267-278. [DOI: https://dx.doi.org/10.1109/TCST.2009.2017934]

12. Abdolhosseini, M.; Zhang, Y.M.; Rabbath, C.A. An Efficient Model Predictive Control Scheme for an Unmanned Quadrotor Helicopter. J. Intell. Robot. Syst.; 2012; 70, pp. 27-38. [DOI: https://dx.doi.org/10.1007/s10846-012-9724-3]

13. Salzmann, T.; Kaufmann, E.; Arrizabalaga, J.; Pavone, M.; Scaramuzza, D.; Ryll, M. Real-Time Neural MPC: Deep Learning Model Predictive Control for Quadrotors and Agile Robotic Platforms. IEEE Robot. Autom. Lett.; 2023; 8, pp. 2397-2404. [DOI: https://dx.doi.org/10.1109/LRA.2023.3246839]

14. Carlos, B.B.; Sartor, T.; Zanelli, A.; Frison, G.; Burgard, W.; Diehl, M.; Oriolo, G. An Efficient Real-Time NMPC for Quadrotor Position Control Under Communication Time-Delay. Proceedings of the 2020 16th International Conference on Control, Automation, Robotics and Vision (ICARCV); Shenzhen, China, 13–15 December 2020; IEEE: Piscataway, NJ, USA, 2020.

15. Zheng, L.; Wang, X.; Li, F.; Mao, Z.; Tian, Z.; Peng, Y.; Yuan, F.; Yuan, C. A Mean-Field-Game-Integrated MPC-QP Framework for Collision-Free Multi-Vehicle Control. Drones; 2025; 9, 375. [DOI: https://dx.doi.org/10.3390/drones9050375]

16. Gill, P.E.; Murray, W.; Saunders, M.A. SNOPT: An SQP Algorithm for Large-Scale Constrained Optimization. SIAM Rev.; 2005; 47, pp. 99-131. [DOI: https://dx.doi.org/10.1137/S0036144504446096]

17. Diehl, M.; Findeisen, R.; Allgöwer, F.; Bock, H.; Schlöder, J. Nominal stability of real-time iteration scheme for nonlinear model predictive control. IEE Proc.-Control. Theory Appl.; 2005; 152, pp. 296-308. [DOI: https://dx.doi.org/10.1049/ip-cta:20040008]

18. Dong, D.; Ye, H.; Luo, W.; Wen, J.; Huang, D. Fast Trajectory Tracking Control Algorithm for Autonomous Vehicles Based on the Alternating Direction Multiplier Method (ADMM) to the Receding Optimization of Model Predictive Control (MPC). Sensors; 2023; 23, 8391. [DOI: https://dx.doi.org/10.3390/s23208391]

19. Ohtsuka, T. A continuation/GMRES method for fast computation of nonlinear receding horizon control. Automatica; 2004; 40, pp. 563-574. [DOI: https://dx.doi.org/10.1016/j.automatica.2003.11.005]

20. Shen, C.; Buckham, B.; Shi, Y. Modified C/GMRES Algorithm for Fast Nonlinear Model Predictive Tracking Control of AUVs. IEEE Trans. Control. Syst. Technol.; 2016; 25, pp. 1896-1904. [DOI: https://dx.doi.org/10.1109/TCST.2016.2628803]

21. Dentler, J.; Kannan, S.; Mendez, M.A.O.; Voos, H. A Real-Time Model Predictive Position Control with Collision Avoidance for Commercial Low-Cost Quadrotors. Proceedings of the 2016 IEEE Conference on Control Applications (CCA); Buenos Aires, Argentina, 19–22 September 2016; IEEE: Piscataway, NJ, USA, 2016.

22. Su, H.; Qi, W.; Hu, Y.; Sandoval, J.; Zhang, L.; Schmirander, Y.; Chen, G.; Aliverti, A.; Knoll, A.; Ferrigno, G. . Towards Model-Free Tool Dynamic Identification and Calibration Using Multi-Layer Neural Network. Sensors; 2019; 19, 3636. [DOI: https://dx.doi.org/10.3390/s19173636]

23. Qi, W.; Ovur, S.E.; Li, Z.; Marzullo, A.; Song, R. Multi-Sensor Guided Hand Gesture Recognition for a Teleoperated Robot Using a Recurrent Neural Network. IEEE Robot. Autom. Lett.; 2021; 6, pp. 6039-6045. [DOI: https://dx.doi.org/10.1109/LRA.2021.3089999]

24. Zhang, J.-X.; Liu, Y.-Q.; Chai, T. Singularity-Free Low-Complexity Fault-Tolerant Prescribed Performance Control for Spacecraft Attitude Stabilization. IEEE Trans. Autom. Sci. Eng.; 2025; 22, pp. 15408-15419. [DOI: https://dx.doi.org/10.1109/TASE.2025.3569566]

25. Liu, M.; Zhang, F.; Lang, S. The Quadrotor Position Control Based on MPC with Adaptation. Proceedings of the 2021 40th Chinese Control Conference (CCC); Shanghai, China, 26–28 July 2021; IEEE: Piscataway, NJ, USA, 2021.

26. Fresk, E.; Nikolakopoulos, G. Full Quaternion Based Attitude Control for a Quadrotor. Proceedings of the 2013 European Control Conference (ECC); Zurich, Switzerland, 17–19 July 2013; IEEE: Piscataway, NJ, USA, 2013.

27. Diebel, J. Representing attitude: Euler angles, unit quaternions, and rotation vectors. Matrix; 2006; 58, pp. 1-35.

28. Hashim, H.A. Special orthogonal group so (3), euler angles, angle-axis, rodriguez vector and unit-quaternion: Overview, mapping and challenges. arXiv; 2019; arXiv: 1909.06669

29. Petersen, L.N.; Poulsen, N.K.; Niemann, H.H.; Utzen, C.; Jørgensen, J.B. Comparison of Linear and Nonlinear Model Predictive Control for Optimization of Spray Dryer Operation. IFAC-PapersOnLine; 2015; 48, pp. 218-223. [DOI: https://dx.doi.org/10.1016/j.ifacol.2015.11.286]

30. Benotsmane, R.; Reda, A.; Vásárhelyi, J. Model Predictive Control for Autonomous Quadrotor Trajectory Tracking. Proceedings of the 2022 23rd International Carpathian Control Conference (ICCC); Sinaia, Romania, 29 May–1 June 2022; IEEE: Piscataway, NJ, USA, 2022.

31. Ohtsuka, T. A tutorial on C/GMRES and Automatic Code Generation for Nonlinear Model Predictive Control. Proceedings of the 2015 European Control Conference (ECC); Linz, Austria, 15–17 July 2015; IEEE: Piscataway, NJ, USA, 2015.

32. Available online: https://www.bitcraze.io/products/crazyflie-2-1-plus/ (accessed on 7 July 2025).

33. Nguyen, K.; Schoedel, S.; Alavilli, A.; Plancher, B.; Manchester, Z. Tinympc: Model-Predictive Control on Resource-Constrained Microcontrollers. Proceedings of the 2024 IEEE International Conference on Robotics and Automation (ICRA); Yokohama, Japan, 13–17 May 2024; IEEE: Piscataway, NJ, USA, 2024.

34. Wang, Z.; Zou, Y.; Liu, Y.; Meng, Z. Distributed Control Algorithm for Leader–Follower Formation Tracking of Multiple Quadrotors: Theory and Experiment. IEEE/ASME Trans. Mechatron.; 2020; 26, pp. 1095-1105. [DOI: https://dx.doi.org/10.1109/TMECH.2020.3017816]

35. Pichierri, L.; Testa, A.; Notarstefano, G. CrazyChoir: Flying Swarms of Crazyflie Quadrotors in ROS 2. IEEE Robot. Autom. Lett.; 2023; 8, pp. 4713-4720. [DOI: https://dx.doi.org/10.1109/LRA.2023.3286814]

36. Budaciu, C.; Botezatu, N.; Kloetzer, M.; Burlacu, A. On the Evaluation of the Crazyflie Modular Quadcopter System. Proceedings of the 2019 24th IEEE International Conference on Emerging Technologies and Factory Automation (ETFA); Zaragoza, Spain, 10–13 September 2019; IEEE: Piscataway, NJ, USA, 2019.

37. Campos, F.M.; Schindler, C.B.; Kilberg, B.G.; Pister, K.S. Lighthouse Localization of Wireless Sensor Networks for Latency-Bounded, high-reliability Industrial Automation Tasks. Proceedings of the 2020 16th IEEE International Conference on Factory Communication Systems (WFCS); Porto, Portugal, 27–29 April 2020; IEEE: Piscataway, NJ, USA, 2020.

38. Robotic Exploration Lab. Tinympc-Crazyflie-Firmware. 2024; Available online: https://github.com/RoboticExplorationLab/tinympc-crazyflie-firmware (accessed on 7 July 2025).

© 2025 by the authors. Licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license (https://creativecommons.org/licenses/by/4.0/). Notwithstanding the ProQuest Terms and Conditions, you may use this content in accordance with the terms of the License.