SDC-Based Model Predictive Control: Enhancing Computational Feasibility for Safety-Critical Quadrotor Control
Abstract
Nonlinear Model Predictive Control (NMPC) is widely used for controlling high-speed robotic systems such as quadrotors. However, its significant computational demands often hinder real-time feasibility and reliability, particularly in environments requiring robust obstacle avoidance. This paper proposes a novel SDC-Based Model Predictive Control (MPC) framework, which preserves the high-precision performance of NMPC while substantially reducing computational complexity by over 30%. By reformulating the nonlinear quadrotor dynamics through the State-Dependent Coefficient (SDC) method, the original nonlinear program problem is transformed into a sequential quadratic optimization problem. The controller integrates an integral action to eliminate steady-state tracking errors and imposes constraints for safety-critical obstacle avoidance. Additionally, a disturbance estimator is incorporated to enhance robustness against external perturbations. Simulation results demonstrate that the SDC-Based MPC achieves comparable tracking accuracy to NMPC, with greater efficiency in terms of computation times, thereby improving its suitability for real-time applications. Theoretical analysis further establishes the stability and recursive feasibility of the proposed approach.
Index Terms:
Model Predictive Control (MPC); State-Dependent Coefficient (SDC); Nonlinear Control Systems; Quadrotors; Unmanned Aerial Vehicles (UAVs); Computational Efficiency; Safety-Critical Control; Robustness.I Introduction
Unmanned aerial vehicles (UAVs), particularly quadrotors, have become increasingly important in both academic research and industry [1]. This growth is mainly due to their low cost, simple design, and ability to move with agility [2]. Quadrotors can take off and land vertically and hover in place, which makes them well-suited for tasks that traditional aircraft cannot handle [3]. They are now used in areas like photography, surveillance, search and rescue, precision agriculture, and package delivery [4]. As a result, improving flight control systems is essential to make the most of these vehicles in real-world situations [5]. Effectively controlling quadrotors presents a unique challenge due to their complex, nonlinear, and underactuated dynamics. Over the years, researchers and engineers have explored a wide range of flight control strategies to address these difficulties. Techniques, such as the Proportional-Integral-Derivative (PID) controller, remain popular for basic flight stabilization because they are straightforward to implement and tune [6]. Nevertheless, PID controllers depend on simplified, linearized models and can struggle to maintain performance during aggressive maneuvers or when faced with unexpected disturbances. To achieve better control in such situations, optimal controllers like the Linear Quadratic Regulator (LQR) are used to systematically compute control gains that minimize a predefined cost function. However, LQR and similar methods are typically effective only under nominal, linearized conditions [7]. Recognizing these shortcomings, nonlinear control approaches have gained traction for their ability to deal with the system’s true dynamics. For example, backstepping uses a stepwise design to guarantee stability, while sliding mode control offers strong resilience to model uncertainties and external disturbances by guiding the system along a specific trajectory [8, 9]. The aforementioned control methods are usually organized in a cascade control structure. This approach simplifies the control problem by separating it into a rapid inner loop for attitude stabilization and a slower outer loop for position tracking [10]. In recent years, learning-based controllers—particularly those leveraging reinforcement learning and neural networks—have shown promise by learning optimal control policies directly from real-world experience, eliminating the need for precise mathematical models [11]. Despite their potential, these methods often require large datasets for training and pose challenges in ensuring safe and reliable operation. Ensuring the safety of autonomous systems is a critical consideration in their synthesis and implementation, which has motivated the development of formally verifiable control methodologies. A prominent approach involves the use of Control Barrier Functions (CBFs), which are employed to render a defined safe set forward invariant. A CBF-based controller minimally modifies a nominal performance-oriented law; this intervention occurs only as the system state approaches the boundary of the safe set, thereby guaranteeing the system does not enter the unsafe region [12]. For stronger safety guarantees, albeit often at a higher computational cost, Reachability Analysis is utilized. This methodology entails the computation of the reachable set—the set of all states attainable by the system—and subsequently verifying that this set does not intersect with predefined unsafe regions [13]. Another influential paradigm leverages Lyapunov-based techniques, which are conventionally applied to stability analysis. In this context, a Lyapunov-like function, referred to as a barrier certificate, is constructed such that its value defines a safe sublevel set of the state space. The control law is then synthesized to ensure the time derivative of the barrier certificate is non-positive, thereby formally confining the system’s evolution to this region [14]. Model Predictive Control (MPC) is an advanced control framework that leverages an explicit system model to predict future behavior over a finite time horizon. At each sampling instant, MPC solves an online optimization problem to find an optimal sequence of control inputs, after which only the first input is applied in a strategy known as a receding horizon. Its primary strength lies in its ability to explicitly incorporate system constraints, making it highly suitable for safety-critical applications. The nature of the underlying optimization is dictated by the system model and constraints; linear systems with quadratic costs result in a solvable Quadratic Program (QP), while fully nonlinear systems require solving a computationally intensive Nonlinear Program (NLP). Building upon this core framework, several powerful variants have been developed. Nonlinear MPC (NMPC) directly uses a nonlinear model for high-fidelity prediction at the cost of significant online computation. To address this computational burden, Explicit MPC (EMPC) pre-computes the optimal control law offline as a piecewise affine function of the state, reducing the online effort to a simple function evaluation but is limited to lower-dimensional systems [15]. To handle real-world uncertainties, Robust MPC provides worst-case guarantees. A prominent implementation is Tube MPC, where a nominal trajectory is optimized and a separate feedback controller ensures the actual system state remains within a robust "tube" around this path, containing all possible deviations due to uncertainty. For probabilistic disturbances, Stochastic MPC (SMPC) optimizes expected performance while satisfying chance constraints [16]. Furthermore, modern Learning-based MPC integrates machine learning to learn system dynamics from data, adapting its predictive model over time [17]. Despite its versatility, MPC’s performance is fundamentally reliant on the accuracy of the predictive model, and its significant online computational demand can render it unsuitable for systems with very fast dynamics or limited onboard processing power. This paper addresses the critical challenge of developing safe, robust, and computationally tractable control systems for quadrotor unmanned aerial vehicles (UAVs). A comprehensive simulation framework was established in MATLAB, utilizing CasADi for numerical optimization, to systematically evaluate three distinct Model Predictive Control (MPC) architectures. The controllers were benchmarked against a challenging trajectory tracking mission requiring static obstacle avoidance amidst stochastic external disturbances. The evaluated strategies include a high-fidelity Nonlinear MPC (NMPC), which solves the full nonlinear optimal control problem and serves as a performance benchmark, alongside two novel quasi-linear formulations. The primary contribution of this research is the development of a robust, computationally efficient MPC that leverages a State-Dependent Coefficient (SDC) representation of the quadrotor’s nonlinear dynamics. This technique reformulates the system equations into a pseudo-linear form, which enables the nonlinear optimal control problem to be effectively approximated as a Quadratic Program (QP) at each sampling instant, significantly reducing computational complexity compared to the full NLP. Building upon this efficient foundation, we introduce a Robust SDC-based MPC (R-SDC-MPC). This advanced controller integrates a real-time disturbance observer that estimates lumped model uncertainties and external disturbances from the one-step state prediction error. This disturbance estimate is then used to actively compensate the predictive model, enhancing the controller’s resilience. Through quantitative analysis of tracking accuracy (MSE), computational load (CPU time), and overall cost, our work demonstrates that the proposed R-SDC-MPC offers a compelling trade-off, achieving robustness and performance comparable to NMPC while maintaining the computational tractability of a QP-based approach.
The remainder of this paper is organized as follows. Section II presents the nonlinear dynamical model of the quadrotor and details its reformulation into the State-Dependent Coefficient (SDC) representation. Section III develops the proposed control framework, starting with the NMPC benchmark, followed by the nominal SDC-MPC design, and culminating in the robust controller with disturbance estimation. In Section IV, a comprehensive simulation study is presented to validate the performance of the proposed methods, with a focus on tracking accuracy, computational efficiency, and safety. Finally, Section V concludes the paper with a summary of the key findings and outlines directions for future research.
II Quadrotor Dynamics and Problem Formulation
II-A Nonlinear Quadrotor Model
In this work, we adopt the six-degree-of-freedom (6-DoF) rigid-body model for the quadrotor, as formulated in [6, 18]. Figure 1 shows the 6-DoF quadrotor model, illustrating the inertial and body-fixed frames, the primary forces of thrust and gravity, and the control torques for roll, pitch, and yaw.

The 12-dimensional state vector is defined as:
(1) |
where is the position in the inertial frame, is the velocity in the inertial frame, represents the Euler angles (roll, pitch, yaw), and is the angular velocity vector in the body frame. The control input vector consists of the total thrust and the three body-axis torques :
(2) |
The translational and rotational dynamics are governed by the Newton-Euler equations:
(3) | ||||
(4) | ||||
(5) | ||||
(6) |
where is the total mass, is the inertia matrix, and is the acceleration due to gravity. The thrust vector in the body frame is . The matrix is the rotation matrix mapping vectors from the body frame to the inertial frame, and is the kinematic transformation matrix from body rates to Euler angle rates.
II-B SDC Representation
A general continuous-time nonlinear dynamical system can be expressed as:
(5) |
where and are the system state vector and the control input vector, respectively; is the initial-valued vector of the states. For the purpose of control design, a possible way to express the dynamical system in (5) is as:
(6a) | ||||
(6b) |
where is the system output vector; , , and are assumed to be smooth. The matrix-valued functions in (6) are assumed to be smooth and satisfy . Therefore, these functions can be written in their pseudo-linearized or SDC forms:
(8a) | ||||
(8b) |
where , and are two matrix-valued functions. It is important to note that there are infinite ways to write pseudo-linearized non-scalar systems which allow an additional level of flexibility to select [25]. The specific factorization used in this work is chosen for its straightforward derivation from the Newton-Euler equations and its ability to isolate the control inputs in the matrix, which is advantageous for control design. Furthermore, this structure has been shown to maintain the necessary stabilizability and detectability properties for a wide range of operating conditions. Now that the matrices are expressed in SDC form, the system can be written as follows:
(9a) | ||||
(9b) |
we consider a full state-feedback control problem, where the entire state vector is assumed to be available to the controller at each time instant. Consequently, the system output is the state itself, rendering a separate output equation unnecessary for the control formulation. The dynamics of the quadrotor are therefore represented by the following SDC-based pseudo-linear model:
(7) |
where . The system matrix is:
(8) |
where the non-zero, state-dependent blocks are defined as:
(9) | ||||
(10) | ||||
(11) |
Here is the identity matrix and is zero matrix. is the partial derivative of the rotation matrix with respect to the Euler angles. is the partial derivative of the kinematic transformation. is the skew-symmetric matrix operator. For a comprehensive review of related quasi-linear control methodologies, including the closely allied State-Dependent Riccati Equation (SDRE) framework, the reader is referred to the works in [19, 20, 21, 22].
II-C SDC-Based Optimal Control Problem Formulation
The main idea of the proposed SDC-based MPC framework is an online optimization problem solved at each sampling instant . This problem aims to compute an optimal control input sequence over a finite prediction horizon, , that steers the quadrotor along a time-varying reference trajectory, . Given the current state , the finite-horizon optimal control problem is formulated as follows:
(12a) | ||||
(12b) | ||||
(12c) | ||||
(12d) | ||||
(12e) |
where the optimization is performed over the control input sequence for all . The objective function in (12a) is composed of a running cost and a terminal cost. The integral term represents the running cost, which penalizes the deviation of the predicted state trajectory from the reference as well as the magnitude of the control input . The semi-positive-definite and positive-definite weighting matrices and , respecetivly, allow for tuning the trade-off between tracking accuracy and control effort. The terminal cost, weighted by the matrix , penalizes the final state error and is crucial for proving closed-loop stability. The optimization is subject to several constraints that define the system’s behavior and limitations.
-
•
The differential equation (12b) enforces the system’s SDC dynamics throughout the prediction horizon.
-
•
Constraints (12c) and (12d) confine the state and control inputs to their respective admissible sets. The input constraint set, , directly represents the physical limitations of the actuators (e.g., maximum thrust and torques). The state constraint set, , is paramount for defining the safe operating envelope. For safety-critical tasks such as obstacle avoidance, this set is explicitly structured to exclude unsafe regions of the state-space. By imposing such constraints, the MPC controller is forced to find a control sequence that guarantees the predicted trajectory remains entirely within the safe region.
-
•
Finally, the terminal inequality constraint(12e) compels the predicted state to lie within a terminal set at the end of the horizon. This set is typically defined relative to the reference state and is essential for guaranteeing the recursive feasibility and stability of the closed-loop system.
Finally, a primary objective of this work is to improve the computational efficiency of the online optimization, ensuring the controller is feasible for real-time implementation without sacrificing performance or violating system constraints.
III Design of the SDC-Based MPC Framework
III-A NMPC Benchmark
The NMPC benchmark is based on the quasi-infinite horizon scheme proposed in [23]. At each sampling instant , the controller solves the following finite-horizon optimal control problem for the current state :
(13a) | ||||
(13b) | ||||
(13c) | ||||
(13d) | ||||
(13e) |
where the terminal penalty matrix is a positive-definite, symmetric matrix chosen to guarantee stability [23]. It is computed off-line as the unique solution to the Lyapunov equation:
(14) |
where is the closed-loop matrix of the system’s Jacobian linearization, and is a tuning parameter [23]. is a locally stabilizing state feedback gain determined linearized system, typically by solving the LQR problem [24]. The terminal region is an invariant set for the nonlinear system under a local linear state feedback law [23]. It is defined as a level set of the Lyapunov function, , where is chosen to ensure that for any state within , the corresponding linear control input satisfies the constraint [23]. The explicit use of a general nonlinear dynamics model, fundamentally casts the optimal control problem as a non-convex NLP. Solving such an NLP is computationally demanding and challenging when the predicted trajectory interacts with the boundaries of the constraint sets. This is particularly for safety-critical applications where complex state constraints, , are activated to enforce collision avoidance by proscribing certain regions of the state-space. The computational burden can render real-time implementation infeasible. Moreover, the reliance on a local linearization to prove stability introduces significant conservatism for systems with prominent nonlinearities. The terminal region where the linear approximation is valid can be impractically small [23]. This necessitates a longer prediction horizon, , to ensure the optimization problem remains feasible, which in turn increases the computational burden and can severely restrict the controller’s effective region of attraction.
III-B Nominal SDC-Based MPC Formulation
To address the computational challenges inherent to the NMPC benchmark, the nominal SDC-MPC scheme is proposed. The primary advantage of this approach is its ability to reformulate the computationally intensive NLP into a sequence of QP with utilization of the SDC representation into the dynamic constraint. By parameterizing the system matrices with the most recent state measurement, the dynamic constraint for the optimal control problem is rendered as a affine system. This model is unique to each time step, as the matrices and are re-calculated based on the new state measurement. This transformation of the dynamics into a set of linear equality constraints is critical. When combined with a quadratic objective function and convex state and input constraints, it ensures that the overall optimal control problem becomes a convex QP. This QP can be solved efficiently and reliably, avoiding the complexities and computational burden of the original NLP. Another key consequence of SDC formulation is that the terminal penalty matrix, , also becomes state-dependent. Consequently, a unique terminal penalty matrix, , must be computed at each time step based on the current state measurement to ensure stability of the system. With considering this, at each state , the State-Dependent Lyapunov Equation (SDLE) is formulated to find the positive-definite matrix that satisfies:
(15) |
where the existence of a positive-definite solution for all in a given domain is a sufficient condition for local stability. The existence of a unique, positive-definite solution to SDLE is contingent upon the stability of the closed-loop system, which is directly determined by the feedback gain matrix . This gain is the sub-optimal state feedback controller, computed as
(16) |
and is designed to stabilize the system at the state . The gain itself is derived from the solution of the State-Dependent Riccati Equation (SDRE), given by:
(17) |
Therefore, the existence of a positive-definite solution to the Lyapunov equation depends on finding a stabilizing solution to the Riccati equation. While solving the SDRE and SDLE at each time step introduces a computational overhead, this process is typically very fast for systems of this dimension and its cost is included in the total per-iteration CPU times reported in Section IV. For the quadrotor model, this overhead was found to be a small fraction of the total optimization time. Under the following theorem, we can guarantee that the SDRE solution is feasible [19].
Theorem 1 (Existence of a Stabilizing SDRE Solution).
For a nonlinear system in SDC form, a unique, positive-definite stabilizing solution to the State-Dependent Riccati Equation (17) exists at a state if the following state-dependent pairs are pointwise stabilizable and detectable, respectively [19, 25]:
-
1.
The pair is stabilizable.
-
2.
The pair is detectable.
The fundamental argument for establishing recursive feasibility is conceptually consistent for SDC based MPC and linear MPC schemes. This argument relies on constructing a feasible candidate solution for the current time step using the optimal solution from the preceding step. Therefore, the proof of recursive feasibility is contingent upon a key assumption regarding the system’s local dynamics and a constructive lemma that guarantees the existence of the necessary terminal ingredients. Nevertheless, the theoretical underpinnings of the proof and its practical implications diverge significantly due to the state-dependent, nonlinear nature of the SDC framework.
Assumption 1 (Stabilizability of the Linearization).
The Jacobian linearization of the system at the origin, represented by the pair of matrices , is stabilizable [23].
This assumption is fundamental, as it ensures that the system can be locally stabilized, which is a prerequisite for constructing a valid terminal set for the MPC. This leads to the following critical lemma.
Lemma 2 (Existence of Terminal Ingredients).
With this foundation, we can formally state and prove the recursive feasibility of the controller.
Theorem 3 (Recursive Feasibility).
If Assumption 1 holds and the optimization problem is feasible at the initial time , then a feasible solution is guaranteed to exist for all subsequent time steps .
Proof.
The proof is by induction. Assume a feasible optimal solution exists at time , yielding the control sequence and state trajectory , which satisfies the terminal constraint . At the next sampling instant, , we construct a candidate solution for the new horizon by using the tail of the previous solution and appending the terminal control law:
(18) |
where the existence of the stabilizing gain and the terminal set is guaranteed by Lemma 2. This candidate is feasible because the terminal state lies in , which is a positively invariant set under the control law . Therefore, the new terminal state at is also guaranteed to be in , satisfying the terminal constraint. Since a feasible solution can be constructed, the optimization problem remains feasible for all subsequent steps [23, 27]. ∎
The determination of a locally stabilizing feedback gain, derived from the Jacobian linearization of the system at its equilibrium, constitutes the foundational prerequisite for the recursive feasibility proof. This concept is illustrated conceptually in Figure 2. This off-line synthesis of a stabilizing terminal controller and an associated invariant terminal set enables the construction of a feasible candidate solution at each subsequent sampling instant, thereby satisfying the conditions required to guarantee recursive feasibility.

III-C Robust SDC-Based MPC with Disturbance Estimation
To enhance the controller’s resilience against inevitable model-plant mismatch and external disturbances, we extend the nominal SDC-based MPC framework with a robust formulation. This is achieved by designing a disturbance observer to actively estimate and compensate for uncertainties. The true system dynamics are modeled as being affected by a lumped disturbance term, , which represents the combined effects of parametric uncertainties, unmodeled dynamics, and exogenous forces:
(19) |
where is the vector of unknown disturbance forces and torques, and is the disturbance input matrix. To ensure the tractability of the estimation problem, a standard assumption is made on the nature of this disturbance.
Assumption 2 (Disturbance Characteristics).
The lumped disturbance is assumed to be bounded and slowly time-varying, such that its rate of change is negligible over a single sampling interval, i.e., for [28].
Under this assumption, a discrete-time state-observer is designed to estimate the disturbance in real-time. The estimation process at each sampling instant involves computing the one-step state prediction error, , which is the discrepancy between the measured state, , and the state predicted from the previous control action using the nominal model:
(20) |
This prediction error is used to infer the disturbance that acted on the system, yielding a raw measurement, . To reduce sensitivity to measurement noise, this estimate is passed through a first-order low-pass filter:
(21) |
The observer gain determines the trade-off between the observer’s convergence rate and its noise sensitivity. The gain was selected empirically as 0.9 to provide a balance between responsiveness to changing disturbances and rejection of high-frequency measurement noise.
Lemma 4 (Observer Error Boundedness).
This disturbance estimate, , is subsequently injected into the MPC’s internal prediction model as a corrective offset term. For the optimization performed at time , the pseudo-linear prediction dynamics are given by:
(22) |
Remark 1 (On the SDC Prediction Model).
The prediction model (22) is an affine system for the duration of a single optimization instance. The matrices , , and are constant within this context. They are obtained by evaluating the state-dependent matrices and at a specific operating point, such as the current state . This approach differs fundamentally from Jacobian linearization; it is an exact algebraic restructuring that fully captures the nonlinearities at that specific point, rather than an approximation that discards higher-order terms.
By incorporating the disturbance estimate, the controller actively accommodates for the disturbance over its prediction horizon. The stability of the composite observer-controller system can be analyzed by considering the separation principle, where the stability of the nominal MPC and the boundedness of the observer error together ensure the ultimate boundedness of the closed-loop system states [30]. The formal verification of recursive feasibility and stability is essential for this robust control architecture. In the presence of persistent disturbances, the objective shifts from proving nominal asymptotic stability to ensuring that the optimization remains feasible despite the model-plant mismatch and that the system state is ultimately bounded within a small neighborhood of the reference trajectory. These properties are typically established by constructing a robustly invariant terminal set and employing an Input-to-State Stability (ISS) framework in the Lyapunov analysis [30, 26]. The implementation of the proposed robust SDC-based MPC is formally outlined in Algorithm 1. The algorithm proceeds iteratively at each sampling instant ; it first updates the disturbance estimate using the measured state and the one-step prediction error from the nominal model.
IV Simulation Results and Performance Analysis
To validate the theoretical claims and quantitatively assess the performance of the proposed control frameworks, a comprehensive simulation study was conducted. The study benchmarks three distinct controllers: the high-fidelity NMPC, the nominal SDC-MPC, and the proposed Robust SDC-based MPC. The controllers were evaluated on a challenging, safety-critical mission requiring a quadrotor to track a dynamic reference trajectory while actively avoiding a static cylindrical obstacle. To simulate realistic operating conditions, the system was subjected to stochastic external disturbances affecting both translational and rotational dynamics. All simulations were implemented in MATLAB R2025b, utilizing the CasADi optimization framework with the IPOPT solver for both the NLP and QP problems. The IPOPT solver was used for all optimization problems to ensure a fair comparison focused on the complexity of the problem formulations, independent of solver-specific optimizations. It is noted, however, that employing a dedicated QP solver for the SDC-based methods could potentially yield even greater computational speed-ups. The computations were executed on a personal laptop equipped with an Apple M4 processor and 24 GB of RAM, providing a consistent hardware baseline for comparing the computational performance of each controller. A consistent set of parameters was used across the simulation to ensure a fair comparison. The quadrotor model was configured with a mass kg and moments of inertia kgm2 and kgm2. For the MPC design, a sampling time of s and a prediction horizon of steps were chosen. The objective function weighting matrices were defined as and . The control inputs were constrained to . The static obstacle was modeled as a vertical cylinder centered at with a radius of m. Finally, the external disturbances were modeled as zero-mean Gaussian noise with standard deviations of for forces and for torques. Figure 3 presents the trajectory of the quadrotor, providing a qualitative assessment of tracking performance and safety constraint satisfaction for the three controllers. A primary observation is that all three methods successfully navigate the static obstacle, deviating from the reference path to maintain a safe distance as enforced by the MPC constraints; this confirms the efficacy of the obstacle avoidance formulation. A comparative analysis of the trajectories reveals the superior performance of the proposed Robust SDC-based MPC, which maintains significantly tighter adherence to the reference path despite the presence of stochastic disturbances. In contrast, both the NMPC and the nominal SDC-MPC exhibit more pronounced oscillations and tracking errors. The inset provides a magnified view of the trajectories near the barrier, confirming that all controllers respect the required safety margin.

A quantitative comparison of the controllers’ performance is summarized in Table I. The table presents three key metrics: the average CPU time required per control step, the Mean Squared Error (MSE) for position tracking, and the total accumulated cost over the entire mission. These metrics provide a clear and concise assessment of the trade-offs between computational efficiency, tracking accuracy, and overall control effort for each of the benchmarked methods.
Metric | NMPC | SDC-MPC | Robust SDC-MPC |
---|---|---|---|
Avg. CPU (ms) | 25.85 | 16.28 | 16.40 |
MSE () | 0.0304 | 0.0302 | 0.0321 |
Total Cost | 5.47e+04 | 5.49e+04 | 5.44e+04 |

The per-iteration computational performance, depicted in Figure 4, further reinforces the advantages of the proposed SDC-based methods. The plot illustrates the CPU time required to solve the optimization problem at each control step. A consistent trend is observed where both the nominal and robust SDC-based controllers exhibit a significantly lower computational burden compared to the full NMPC benchmark. This efficiency is particularly critical during the most demanding phase of the mission, from approximately 11 to 13 seconds, where the safety constraints for obstacle avoidance become highly active. During this period, the solution time for all controllers increases, yet the SDC-based methods remain substantially faster, confirming their suitability for real-time implementation in computationally constrained, safety-critical scenarios. Figure 5 illustrates the evolution of the optimal cost function value, , at each time step for the three controllers. The cost value serves as a proxy for the controller’s perceived difficulty in satisfying its objectives; higher costs indicate a greater combined penalty from tracking errors, control effort, and constraint violations. The plot reveals several distinct phases: an initial transient phase where the cost decreases as the quadrotor converges to the path, a significant increase in cost during the obstacle avoidance maneuver (around 11-13 seconds) where the controller must balance tracking with safety, and subsequent periods of stabilization. Notably, the cost profiles for all three controllers are qualitatively similar, indicating that the SDC-based methods achieve comparable overall performance to the NMPC benchmark, as corroborated by the total cost values in Table I.

The position tracking performance in the X, Y, and Z axes is detailed in Figure 6. All controllers effectively track the time-varying reference trajectory across all three dimensions. The top subplot shows the X-position, where the step change in the reference after 4 seconds is handled well by all methods, though the Robust SDC-MPC demonstrates the least overshoot. The middle and bottom subplots for the Y and Z positions further highlight the superior tracking accuracy of the Robust SDC-MPC, which exhibits smaller deviations from the reference, especially during the dynamic circular portion of the trajectory. This improved performance is directly attributable to the disturbance observer, which actively compensates for unmodeled dynamics and external perturbations, leading to more precise tracking.

To further quantify the tracking accuracy, the squared position error for each controller is plotted over time in Figure 7. This plot corroborates the qualitative observations from previous figures and provides a clearer view of the performance differences, particularly due to the logarithmic scale. The Robust SDC-MPC consistently achieves the lowest tracking error throughout the simulation, with error levels often an order of magnitude smaller than the other controllers, especially during less dynamic phases of the trajectory (e.g., around 10 seconds and 15 seconds). This demonstrates the effectiveness of the disturbance observer in actively rejecting perturbations and reducing steady-state tracking error, a conclusion strongly supported by the lower overall MSE for this controller reported in Table I.

IV-A Discussion of Limitations
While the proposed SDC-based framework demonstrates significant advantages, it is important to acknowledge its limitations. The performance of the robust controller relies on the assumption that disturbances are slowly time-varying. Its effectiveness may be reduced in the presence of high-frequency or abrupt disturbances that violate this assumption. Additionally, the SDC method is an exact algebraic transformation at a specific point in time. For highly aggressive maneuvers over a long prediction horizon, the system state may diverge significantly from the point of linearization, potentially degrading the accuracy of the prediction model. The stability and recursive feasibility guarantees also rely on a terminal set derived from a local linearization, which, while standard, may be conservative. Future work will seek to address these limitations, potentially through the use of more advanced disturbance observers or adaptive prediction models.
V Conclusion
This paper addressed the challenge of implementing high-performance, safety-critical control for quadrotors under significant computational constraints. We proposed a novel SDC-based MPC framework and a robust extension that incorporates a disturbance observer. The SDC reformulation allows the nonlinear optimal control problem to be solved as a sequence of computationally efficient QPs, directly addressing the limitations of traditional NMPC. The simulation results conclusively demonstrate the efficacy of the proposed approach. The Robust SDC-based MPC not only matched the safety and tracking performance of the NMPC benchmark but, through active disturbance compensation, achieved superior tracking accuracy. Critically, this enhanced performance was realized with a significant reduction in computational time, with the SDC-based methods proving to be over 30% faster on average than the NMPC. The key contribution of this work is the demonstration that the SDC-based methodology successfully achieves a compelling balance between safety-critical performance and computational efficiency, establishing it as a highly feasible alternative to NMPC for real-time quadrotor applications. Future research will prioritize the experimental validation of the proposed controller on a physical quadrotor platform, which will be crucial for assessing its real-world performance under conditions of sensor noise and communication latency. Further avenues of investigation include the exploration of more advanced disturbance estimation techniques, the development of adaptive SDC formulations to handle highly aggressive maneuvers, and the extension of this computationally efficient framework to cooperative control of multi-agent aerial systems.
References
- [1] J. Peksa and D. Mamchur, “A review on the state of the art in copter drones and flight control systems,” Sensors, vol. 24, no. 11, p. 3349, 2024.
- [2] S. Allan and M. Barczyk, “A low-cost experimental quadcopter drone design for autonomous search-and-rescue missions in gnss-denied environments,” Drones, vol. 9, no. 8, p. 523, 2025.
- [3] Y. Wang, H. Ji, Q. Kang, H. Qi, and J. Wen, “Autonomous trajectory control for quadrotor evtol in hover and low-speed flight via the integration of model predictive and following control,” Drones, vol. 9, no. 8, p. 537, 2025.
- [4] S. S. Unde, V. Kurkute, S. S. Chavan, D. D. Mohite, A. A. Harale, and A. Chougle, “The expanding role of multirotor uavs in precision agriculture with applications ai integration and future prospects,” Discover Mechanical Engineering, vol. 4, no. 1, pp. 1–26, 2025.
- [5] M. Rinaldi, S. Primatesta, and G. Guglieri, “A comparative study for control of quadrotor uavs,” Applied Sciences, vol. 13, no. 6, p. 3464, 2023.
- [6] C. Massé, O. Gougeon, D.-T. N’Guyen, and D. Saussié, “Modeling and control of a quadcopter flying in a wind field: A comparison between lqr and structured h control techniques,” in 2018 International Conference on Unmanned Aircraft Systems (ICUAS). IEEE, 2018, pp. 1408–1417.
- [7] C.-C. Chen and Y.-T. Chen, “Feedback linearized optimal control design for quadrotor with multi-performances,” IEEE Access, vol. 9, pp. 26 674–26 695, 2021.
- [8] J. Wang, K. A. Alattas, Y. Bouteraa, O. Mofid, and S. Mobayen, “Adaptive finite-time backstepping control tracker for quadrotor uav with model uncertainty and external disturbance,” Aerospace Science and Technology, vol. 133, p. 108088, 2023.
- [9] B. Mu, K. Zhang, and Y. Shi, “Integral sliding mode flight controller design for a quadrotor and the application in a heterogeneous multi-agent system,” IEEE Transactions on Industrial Electronics, vol. 64, no. 12, pp. 9389–9398, 2017.
- [10] S. Bouabdallah, A. Noth, and R. Siegwart, “PID vs LQ control techniques applied to an indoor micro quadrotor,” in 2004 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)(IEEE Cat. No. 04CH37566), vol. 1. IEEE, 2004, pp. 345–350.
- [11] J. Hwangbo, I. Sa, R. Siegwart, and M. Hutter, “Control of a quadrotor with reinforcement learning,” IEEE Robotics and Automation Letters, vol. 2, no. 4, pp. 2096–2103, 2017.
- [12] A. D. Ames, S. Coogan, M. Egerstedt, G. Notomista, K. Sreenath, and P. Tabuada, “Control Barrier Functions: Asymptotic Safety and Stability,” IEEE Transactions on Automatic Control, vol. 62, no. 7, pp. 3161–3176, 2017.
- [13] I. M. Mitchell, “A toolbox of level set methods,” in Proceedings of the 2005 international conference on Svetlogorsk. Citeseer, 2005, pp. 1–12.
- [14] S. Prajna, A. Jadbabaie, and G. J. Pappas, “A framework for analysis of nonlinear systems using barrier certificates,” IEEE Transactions on Automatic Control, vol. 52, no. 1, pp. 23–35, 2007.
- [15] A. Bemporad, M. Morari, V. Dua, and E. N. Pistikopoulos, “The explicit linear quadratic regulator for constrained systems,” in Automatica, vol. 38, no. 1. Elsevier, 2002, pp. 3–20.
- [16] M. Farina, L. Giulioni, and R. Scattolini, “Stochastic model predictive control: An overview and perspectives for future research,” Annual Reviews in Control, vol. 42, pp. 115–128, 2016.
- [17] U. Rosolia and F. Borrelli, “Learning model predictive control for iterative tasks,” in 2017 IEEE 56th Annual Conference on Decision and Control (CDC). IEEE, 2017, pp. 3272–3277.
- [18] B. Xu, A. Suleman, and Y. Shi, “A multi-rate hierarchical fault-tolerant adaptive model predictive control framework: Theory and design for quadrotors,” Automatica, vol. 153, p. 111015, 2023.
- [19] T. Cimen, “State-dependent riccati equation (sdre) control: A survey,” in Proceedings of the 17th world congress, the international federation of automatic control, vol. 17, no. 1, 2008, pp. 3761–3775.
- [20] J. R. Cloutier, “State-dependent riccati equation techniques: an overview,” in Proceedings of the 1997 American Control Conference, vol. 2. IEEE, 1997, pp. 932–936.
- [21] C. Mracek and J. Cloutier, “Control designs for the nonlinear benchmark problem via the state-dependent riccati equation method,” International Journal of Robust and Nonlinear Control: IFAC-Affiliated Journal, vol. 8, no. 4-5, pp. 401–416, 1998.
- [22] K. D. Hammett, N. Harl, H. An, and E. Zuazua, “State-dependent coefficient factorization for nonlinear optimal feedback control,” IEEE Transactions on Automatic Control, vol. 62, no. 5, pp. 2497–2502, 2016.
- [23] H. Chen and F. Allgöwer, “A Quasi-Infinite Horizon Nonlinear Model Predictive Control Scheme with Guaranteed Stability,” Automatica, vol. 34, no. 10, pp. 1205–1217, 1998.
- [24] J. B. Mare and J. A. De Doná, “Solution of the input-constrained lqr problem using dynamic programming,” Systems & control letters, vol. 56, no. 5, pp. 342–348, 2007.
- [25] Y. Batmani, M. Davoodi, and N. Meskin, “Nonlinear suboptimal tracking controller design using state-dependent riccati equation technique,” IEEE Transactions on Control Systems Technology, vol. 25, no. 5, pp. 1833–1839, 2016.
- [26] J. B. Rawlings, D. Q. Mayne, and M. M. Diehl, Model Predictive Control: Theory, Computation, and Design. Nob Hill Publishing, 2017, vol. 2.
- [27] J. B. Rawlings and K. R. Muske, “The stability of constrained receding horizon control,” IEEE Transactions on Automatic Control, vol. 38, no. 10, pp. 1512–1516, 1993.
- [28] W.-H. Chen, J. Yang, L. Guo, and S. Li, “Disturbance-observer-based control and related methods—an overview,” IEEE Transactions on Industrial Electronics, vol. 63, no. 2, pp. 1083–1095, 2016.
- [29] H. Wang, D. Zhou, and P. Li, “Disturbance observer-based robust control for nonlinear systems,” Acta Automatica Sinica, vol. 35, no. 6, pp. 721–727, 2009.
- [30] D. Q. Mayne, J. B. Rawlings, C. V. Rao, and P. O. Scokaert, Constrained model predictive control: Stability and optimality. Nob Hill Publishing, 2000, vol. 2.
![]() |
Saber Omidi (Student Member, IEEE) received his B.Sc. degree in Mechanical Engineering from Qazvin Islamic Azad University, Qazvin, Iran, in 2017, and his M.Sc. degree in Mechanical Engineering from University of Kurdistan, Sanandaj, Iran, in 2021. He is currently pursuing his Ph.D. degree in Mechanical Engineering at University of New Hampshire. His research interests include safety-critical control, learning-based control, with applications in autonomous systems and mechanical systems. |