Next Article in Journal
Experiment and Numerical Investigation of a Forebody Design Method for Inward-Turning Inlet
Previous Article in Journal
On the Structural Design and Additive Construction Process of Martian Habitat Units Using In-Situ Resources on Mars
Previous Article in Special Issue
ROS-Based Multi-Domain Swarm Framework for Fast Prototyping
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

ProVANT Simulator: A Virtual Unmanned Aerial Vehicle Platform for Control System Development

1
Graduate Program in Electrical Engineering, Universidade Federal de Minas Gerais, Belo Horizonte 31270-901, MG, Brazil
2
Department of Electrical and Computer Engineering, Universidade de São Paulo, São Carlos 13566-590, SP, Brazil
3
Department of Mechatronics Engineering, Centro Federal de Educação Tecnológica, Divinópolis 35503-822, MG, Brazil
4
Department of Management, Information and Production Engineering, University of Bergamo, 24129 Dalmine, BG, Italy
5
Department of Automation and Systems Engineering, Universidade Federal de Santa Catarina, Florianópolis 88035-972, SC, Brazil
6
Department of Aerospace Engineering and Fluid Mechanics, Universidad de Sevilla, 41092 Sevilla, Andalucía, Spain
7
Department of Electronics Engineering, Universidade Federal de Minas Gerais, Belo Horizonte 31270-901, MG, Brazil
*
Author to whom correspondence should be addressed.
Aerospace 2025, 12(9), 762; https://doi.org/10.3390/aerospace12090762
Submission received: 1 July 2025 / Revised: 15 August 2025 / Accepted: 18 August 2025 / Published: 25 August 2025

Abstract

This paper introduces the ProVANT Simulator, a comprehensive environment for developing and validating control algorithms for Unmanned Aerial Vehicles (UAVs). Built on the Gazebo physics engine and integrated with the Robot Operating System (ROS), it enables reliable Software-in-the-Loop (SIL) and Hardware-in-the-Loop (HIL) testing. Addressing key challenges such as modeling complex multi-body dynamics, simulating disturbances, and supporting real-time implementation, the framework features a modular architecture, an intuitive graphical interface, and versatile capabilities for modeling, control, and hardware validation. Case studies demonstrate its effectiveness across various UAV configurations, including quadrotors, tilt-rotors, and unmanned aerial manipulators, highlighting its applications in aggressive maneuvers, load transportation, and trajectory tracking under disturbances. Serving both academic research and industrial development, the ProVANT Simulator reduces prototyping costs, development time, and associated risks.

1. Introduction

The development of robotic systems has garnered significant attention due to their expanding range of applications. Robot design typically involves the integration of mechanical structures, hardware components, and software systems. During the development process, control hardware and software can be tested directly on the physical prototype. However, this approach carries substantial safety risks, including potential equipment damage and, in severe cases, injuries or fatalities. These risks are particularly critical in Unmanned Aerial Vehicles (UAVs), which often feature powerful actuators, fast-moving parts, and, in some instances, heavy payloads. Moreover, accidents during prototyping can significantly increase costs and extend development time, creating serious challenges for institutions and researchers with limited resources. In this context, system simulations offer a practical and cost-effective alternative. They support the development, validation, tuning, and optimization of advanced control strategies without the need for physical implementations, while also mitigating the risks associated with prototype failures.
Developing reliable control strategies and implementing them in hardware for robots involves addressing several inherent challenges, including meeting real-time execution requirements, debugging complex control code, handling high nonlinear dynamics with several degrees of freedom (DOF), and ensuring robustness. In light of these challenges, this paper introduces the ProVANT Simulator (The ProVANT Simulator can be accessed at https://github.com/ProVANT-Project/ProVANT_Simulator, along with its comprehensive User Manual.), a realistic and versatile simulation platform designed to support the development and validation of robotic control algorithms.
ProVANT is a collaborative project dedicated to the design and development of Unmanned Aerial Vehicles (UAVs). Initiated in 2013, it brings together two Brazilian universities—the Federal University of Minas Gerais and the Federal University of Santa Catarina—and international partners such as the University of Seville in Spain. The project encompasses various aspects of UAV development, including airframe design, electronic systems, and software, with particular emphasis on advanced control strategies.
The ProVANT Simulator supports Software-in-the-Loop (SIL) experiments, in which control strategies are executed on a general-purpose computer. This setup is particularly useful during the early stages of development, allowing for debugging and preliminary performance assessment in a controlled environment. However, SIL simulations do not always reflect the constraints of real-world deployment, as there are often significant differences in processing power, memory, and timing behavior between desktop workstations and the embedded platforms used in actual robots. To bridge this gap, the simulator also supports Hardware-in-the-Loop (HIL) experiments, enabling the control software to run directly on the target embedded hardware. This capability enables more accurate performance evaluation under realistic computational conditions, bringing the testing process closer to final deployment.
Although the simulator is primarily designed for advancing UAV technologies, its architecture is general enough to accommodate a wide range of robotic systems. The ProVANT Simulator is built on top of the Gazebo engine, leveraging its high-fidelity physics simulation, extensive library of sensors and actuators, and modular plug-in architecture. Gazebo is widely recognized for its realism and reliability and has been adopted by leading organizations such as the Defense Advanced Research Projects Agency (DARPA) (https://spectrum.ieee.org/darpa-robotics-challenge-simulation-software-open-source-robotics-foundation, accessed on 14 August 2025) and the National Aeronautics and Space Administration (NASA). It has also served as the simulation backbone for several high-profile research initiatives [1,2,3].
Designed to serve both academic research and industrial development, the ProVANT Simulator has been developed by experts in control and aerospace engineering to support a wide range of UAV platforms, including quadrotors, tilt-rotors, and unmanned aerial manipulators. It enables the simulation of complex tasks such as aggressive maneuvers, load transportation, and trajectory tracking across various flight modes—including helicopter, fixed-wing, and transitional phases in tilt-rotor configurations.
The main contributions of this work are twofold. First, we introduce the ProVANT Simulator, an open-source simulation platform released under the MIT license, designed to support the development, testing, and validation of robot control algorithms using visual feedback in both SIL and HIL configurations. Built on a modular architecture using the Robot Operating System (ROS) and Gazebo, it allows for seamless integration with external tools, real-time execution, and fosters reproducibility in experimental research. Second, we validate the simulator with case studies using advanced control strategies from peer-reviewed journals. The results not only confirm the correct implementation of these strategies but also demonstrate the simulator’s realism and effectiveness for high-fidelity UAV simulation and controller evaluation.
The remainder of this paper is structured as follows: Section 2 provides an overview of existing UAV simulation frameworks and highlights their key characteristics. Section 3 describes the main features of the ProVANT Simulator, including its software architecture and integration with widely used development tools. Section 4 presents a series of case studies that demonstrate the simulator’s versatility across various UAV configurations and application scenarios. Finally, Section 5 offers concluding remarks and outlines directions for future research.

2. Related Works

This section reviews key projects and studies on UAV simulation environment, highlighting their contributions, and positioning the ProVANT Simulator within this landscape.
In [4], a platform called AuRoRA has been described for the simulation of rotary-wing UAVs with support for HIL. It includes tools for comprehensive simulation, such as actuator modeling, mathematical representations, and sensor data acquisition from devices like Inertial Measurement Units (IMUs) and Global Positioning Systems (GPS). The platform supports distributed system simulations, facilitating the development of computationally intensive control strategies. However, it is not based on standardized technologies, making it difficult to extend to other UAV types and to incorporate new sensors. Additionally, the lack of visual feedback limits its ability to provide an intuitive representation of the simulation environment.
Similarly, RotorS [5] is a simulation project developed at ETH Zurich, focusing on aerial robots. It provides ready-to-use models for several multicopters and features the ability to accept commands and output sensor measurements via MAVLink messages [6]. However, as it is specifically designed for aerial robots, it lacks compatibility with other robots types. Moreover, it does not include functionalities for managing the simulation time step, which hinders the simulation of resource-intensive control strategies and results in limited computational performance.
In contrast to simulation-focused software like AuRoRA and RotorS, the main ROS distribution includes the ROS Control package [7], which provides tools for developing robot controllers. Widely used across robotics applications, ROS Control emphasizes high-performance controller development in C++, offering libraries and tools to create real-time controllers and implement common algorithms such as PID controllers. However, this package requires extensive knowledge of ROS and lacks support for higher-level programming languages like MATLAB. Additionally, it has a steep learning curve and demands advanced software development skills for effective use.
Recent surveys have provided further insights into UAV simulation tools, highlighting the available solutions and their targeted applications. For instance, ref. [8] has reviewed over forty UAV simulators, analyzing their benefits, shortcomings, and suitability for research and operational needs. Among these, Gazebo has been emphasized for its modularity and compatibility with robotic frameworks like ROS, making it a popular choice for academic research. FlightGear has been noted for its high-fidelity aerodynamics modeling, but it is less suited for rapid prototyping due to limited extensibility. Meanwhile, X-Plane has been recognized for its industrial-grade physics accuracy, though it comes with a steep learning curve and limited support for custom UAV configurations. The study has underscored important decision factors for selecting simulators, such as extensibility, real-time capabilities, ease of hardware, and computational requirements, providing researchers with guidelines for choosing tools tailored to their specific projects.
Expanding on this topic, ref. [9] has discussed UAV simulation frameworks, particularly focusing on their role in performance testing. It has identified key metrics such as computational load, simulation accuracy, and scalability as primary concerns for researchers. Tools like ArduPilot SITL and PX4 SITL have been highlighted for their integration with real autopilot systems, enabling realistic SIL simulations. The paper has also emphasized the importance of balancing computational efficiency with simulation fidelity, especially for applications requiring real-time performance, such as multi-UAV coordination and path planning algorithms.
In addition to general-purpose tools, specific application-oriented frameworks have been developed. For example, ref. [10] have demonstrated the adaptability of simulation platforms like Unreal Engine for specialized tasks. The paper has emphasized the integration of high-fidelity visualization and environmental modeling to validate UAV flight paths in landslide-prone regions. This approach not only enables realistic testing of flight plans but also provides valuable insights into UAV interactions with complex terrains.
Another notable work, ref. [11], has categorized simulation tools based on their capabilities for testing and validating UAV performance. It has underscored the importance of simulation testbeds for evaluating control algorithms, sensor integration, and mission planning within controlled environments. The paper has highlighted how platforms such as Simulink and Gazebo can be extended to support diverse UAV configurations and facilitate the development of advanced control strategies.
While these tools and frameworks have made significant contributions, many lack comprehensive features such as modularity, support for multiple robots configurations, and seamless integration with real-time systems. The ProVANT Simulator, introduced in this manuscript, addresses these limitations by offering a user-friendly, flexible, and robust environment that combines SIL and HIL simulations within an intuitive graphical interface. To summarize and facilitate comparison of the main UAV simulation platforms reviewed in this section and the ProVANT Simulator, Table 1 presents the most relevant characteristics. The architecture of the ProVANT Simulator is detailed in the following sections.

3. ProVANT Simulator Overview

This section outlines the key features of the developed ProVANT Simulator, emphasizing those most relevant to its primary users, including researchers and developers working on UAV control strategies. A key objective in the development of the ProVANT Simulator was to leverage existing open-source tools and widely adopted standards. This is intended to maximize software reuse, minimize development effort, and ensure interoperability with established frameworks.
Rather than building the simulator from scratch, we based its implementation on the Gazebo platform [12]. Beyond the reasons mentioned in the Introduction, Gazebo was chosen because it meets specific functional requirements for UAV control development. These include providing real-time visual feedback, enabling the construction of complex and dynamic simulation environments, and supporting interactive manipulation of objects and scenarios. Gazebo also offers a rich library of built-in sensors, compatibility with standard robot description formats such as Unified Robot Description Format (URDF) and Simulation Description Format (SDF), and a modular, plugin-based architecture that facilitates extensibility. Furthermore, its native integration with ROS [13] allows for efficient communication between components via ROS topics, supporting asynchronous and event-driven interactions across distributed nodes. Figure 1 presents an overview of the adopted software architecture.

3.1. Simulator Internal Structure

Figure 2 illustrates the internal elements of the ProVANT Simulator, which are represented as containers—modules composed of multiples components. In addition to these software elements, the ProVANT Simulator also includes ready-to-use UAV descriptions, equipped with plugins for state vector measurements and actuator simulation. Figure 2 also highlights the Sensor and Actuator plugin components, which extend Gazebo’s functionalities and provide essential interfaces for developing control strategies.
The Step plugin (located at the top-right portion of Figure 2) is a container that replaces the Gazebo’s standard timing management mechanism, allowing the controller to manage simulation timing. This plugin ensures that the simulation advances only after the control strategy has completed all computations for the current step, regardless of the processing time required.
The GUI container (located on the top-left portion of Figure 2) is designed to simplify simulation setup and debugging. It enables users to create, configure, and execute simulations without relying on the standard command-line tools from ROS and Linux, significantly lowering the learning curve for using the simulator and developing new scenarios. Additionally, the GUI includes features to streamline the creation and compilation of control strategies, as well as tools for inspecting the sensors and actuators available on each robot.
The Models container (located on the middle-left of Figure 2) encompasses all robot descriptions, including their visual and collision meshes, physical parameters, and configuration files. Defined using SDF, these models may incorporate aerodynamic plugins and simulate external disturbances.
The Controller container encompasses all essential functionalities for communication, storage of the simulation results, timing management, and other requirements for executing the control strategies. Figure 3 presents a detailed view of this container, highlighting the user-provided control strategy (bottom) and the data logger component (top), which records simulation data for future analysis.
The Simulation Manager component, illustrated in Figure 3, is responsible for managing simulation timing and coordinating data exchange among system components, thereby ensuring consistent and reproducible execution of experiments in both SIL and HIL configurations.
The Data Logger component enables the ProVANT Simulator to export the simulation data generated to an external file in CSV format. This feature is particularly useful because the resulting file can be imported into external tools such as MATLAB and other similar software for further analysis and visualization, allowing for a detailed assessment of UAV performance during the simulation.
Figure 4 presents the class diagram of the Control Strategy component, which must be implemented by the user when designing a custom control strategy. This implementation is required only if the user wishes to develop a new control strategy. The following methods must be implemented:
  • Config(): This method is called once during the controller’s configuration phase, before the simulation starts. It is responsible for setting up all parameters required for the control strategy, such as defining gain values, initializing integrators, and preparing other necessary resources.
  • Execute(): This method is called at every control step, receiving as a parameter a vector of sensor readings from the current UAV. It computes and generates a vector of control inputs to be applied to the robot, implementing the control law.
  • Reference(): Returns the current reference vector of trajectory values to be tracked by the UAV.
  • Error(): Returns the current error vector of the UAV’s states.
  • State(): Returns the current UAV state vector.

3.2. Graphical User Interface

The GUI of the ProVANT Simulator provides an intuitive and streamlined environment for setting up, configuring, and executing robot simulations. Through this interface, users can manage simulation scenarios, vehicle models, and control strategies efficiently (A detailed explanation of the simulation workflow and graphical interface is available at https://github.com/ProVANT-Project/ProVANT_Simulator/blob/main/user_manual/Manual_ProVANT_Simulator.pdf).
The main window of the GUI is shown in Figure 5, which includes: (1) a hierarchical tree for configuring robot and simulation parameters, such as gravity settings, physics engine selection (e.g., ODE, Bullet, DART, Simbody), robot name, and initial pose. By double-clicking specific fields, users can edit these parameters or access additional configuration tabs for the model, world, controller, sensors, and actuators; (2) a preview panel displaying the selected robot model; (3) a preview of the simulation environment (world); and (4) a button to launch the Gazebo simulator. Robot models are selected through the Edit option in the top menu.
By double-clicking the model entry in the tree structure highlighted in orange (1) (see Figure 5), the Controller tab is opened, as illustrated in Figure 6. Within this tab, users can: (1) select an existing control strategy; (2) create a new one; (3) open and edit an existing strategy; and (4) compile the selected controller. The tab also includes fields to configure (5) the sampling time and to define file paths for (6) tracking error, (7) reference signals, (8) sensor data, and (9) actuator data, facilitating post-analysis of the results. Button (10) confirms and saves the configuration. Still within the Controller tab, users can access the Sensors and Actuators tabs to configure the respective topics. These topics define the ROS interfaces through which the controller will communicate with the simulated system during execution.

3.3. Simulation Modes

The ProVANT Simulator supports both synchronous and asynchronous execution modes in SIL and HIL simulations. While this flexibility benefits both configurations, asynchronous execution is particularly relevant in the HIL context, where additional hardware constraints and communication complexity arise due to the involvement of external embedded systems.
In the asynchronous HIL mode, controllers are validated under conditions compatible with real-time execution, making it suitable for implementations that must comply with strict timing constraints. In this configuration, the embedded system and the simulator operate independently, as shown in Figure 7. The corresponding plugin initializes the HIL Server task, which manages serial communication with the embedded computer. Upon receiving a request, the server either sends the current system state to the embedded device or receives and applies a control signal. Notably, Gazebo’s built-in Real-Time System scheduler is enabled to maintain a real-time factor (RTF) of 1.0 , ensuring one second of simulation time equals one second of wall-clock time. The simulator advances continuously, sustaining the last received control input until it is updated by the HIL Server.
In synchronous HIL mode, which is most appropriate to be used when the embedded system cannot compute the control signal within the system’s sampling time, the simulator assumes the role of master, and the embedded device operates as a slave. As depicted in Figure 8, the HIL plugin initializes a server that transmits the current state vector to the embedded computer and waits for the corresponding control signal. The simulation pauses during this exchange, resuming only after the control signal is received and applied.

3.4. Database of UAV Models

The ProVANT Simulator offers a diverse set of UAV models, providing users with a flexible foundation for various applications. The available models include:
  • Quadrotor UAV;
  • Unmanned aerial manipulator;
  • ProVANT UAV 2 (with and without an external load);
  • ProVANT UAV 3;
  • ProVANT-EMERGENTIA UAV;
  • VERSATILE UAV.
These models come equipped with fully configured components, including sensors and actuators, allowing users to focus on developing and testing control strategies rather than building models from scratch. The next section provides further details on these UAV models. It is worth highlighting that the UAV models used within the simulator are derived from CAD-based designs imported directly from CAD software. Consequently, their exact dynamical mathematical models are not known. This deliberate design choice enables the simulator to function as a crucial tool for validating mathematical models of UAV dynamics under realistic disturbances and uncertainties, in addition to its role as a development platform.

4. Case Studies

This section presents various case studies conducted using the ProVANT Simulator across different UAV models and experimental scenarios. The objective is to thoroughly explore and evaluate the capabilities of the simulator

4.1. Quadrotor UAV in an Urban Environment

This subsection presents a case study in which a quadrotor UAV navigates through an unknown 3D environment, conducted using the ProVANT Simulator. The objective is to evaluate the Nonlinear Model Predictive Control (NMPC) strategy and the obstacle detection algorithms proposed in [14] through SIL experiment. Further details of the quadrotor’s dynamic model can be found in [15].
The simulation was carried out on a computer running Ubuntu 20.04, equipped with an AMD Ryzen 7 3700U processor (1.51 GHz, 4 cores, 8 threads—AMD, Santa Clara, CA, USA) and 20 GB of RAM. The UAV parameters are presented in Table 2. The control system was implemented in MATLAB R2017a with the CasADi toolbox [16].
To integrate the MATLAB-based control system with the ProVANT Simulator, the MATLAB Engine API for C++ was used. This interface allows the C++ controller to invoke an NMPC algorithm implemented in MATLAB by passing system states and sensor data as inputs. The computed control signals are returned and applied as thrust forces on the quadrotor. Figure 9 illustrates the data flow during this process.
During the experiment, the ProVANT Simulator provides the system states at each sample time, including the vehicle’s position, attitude, and linear and angular velocities. Additionally, a 3D LIDAR sensor is emulated within the ProVANT Simulator, supplying data about the environment. Both the system states and the LIDAR data are fed into the controller, which is executed on MATLAB R2024b and uses optimization techniques to compute the desired thrust forces for the rotors. These control inputs are then sent back to the ProVANT Simulator, which updates the rotor thrusts at each sample time.
The NMPC was designed to steer the quadrotor from an initial position x 0 to a desired target x t in minimum time while avoiding obstacles. Environment obstacles detected via the emulated LIDAR sensor were represented as polyhedra using a half-space representation. Obstacle-free zones were decomposed into convex subregions, which served to define constraints in the NMPC optimization problem, which aimed to minimize control effort while ensuring the vehicle remained within the feasible regions defined by the sensor data. Figure 10 shows the block diagram of the control system utilized in the SIL experiment. The NMPC control strategy is computationally demanding and does not meet real-time execution requirements. As a result, the simulation is performed in synchronous mode, allowing the control strategy to be tested while deferring computational optimization to future work. No external disturbances were considered in this case study.
A video of the simulation is available at https://youtu.be/gkPfKWQnCU0. Figure 11 illustrates the quadrotor’s trajectory during the SIL experiment. Figure 12 and Figure 13 show the evolution of the position, linear velocities, attitude, and angular time derivatives, and Figure 14 shows the applied control signals during the SIL experiment. As can be observed, the quadrotor successfully navigated around three obstacles in an unknown environment while maintaining a safe distance, demonstrating the effectiveness of the NMPC strategy and the capabilities of the ProVANT Simulator in simulating complex control scenarios.

4.2. Quadrotor UAV for Aggressive Maneuvers

The primary objective of this section is to evaluate NMPC schemes proposed for aggressive motion control of a quadrotor UAV, using SIL experiments conducted in the ProVANT Simulator. The mathematical modeling and the NMPC control design are described in detail in [17]. A block diagram of the implemented control architecture is presented in Figure 15. The UAV parameters are detailed in Table 2.
As mentioned in the previous subsection, the NMPC control strategy is computationally demanding and does not meet real-time execution requirements. Accordingly, the simulation is performed in synchronous mode, allowing the control strategy to be tested while deferring computational optimization to future work. The SIL experiments were conducted on a general-purpose computer equipped with an Intel Core i7-4500U processor (1.8 GHz) featuring two physical cores and four logical threads, 8 GB of RAM, and an NVIDIA GT 750M GPU. The system ran on Ubuntu Linux version 18.04. No external disturbances are also considered in this case study.
The NMPC controllers are formulated on the SE ( 3 ) manifold, enabling a global and unique representation of the vehicle’s motion. This singularity-free formulation proved advantageous during the experiments, as the quadrotor UAV successfully recovered from an upside-down configuration without the need for additional controllers or optimization layers, as illustrated in Figure 16. A video of the simulations is available at https://youtu.be/rEJB7pTyTB8, and the corresponding results are presented in Figure 17, Figure 18 and Figure 19.
The experiment focused on point-to-point maneuvers, where the vehicle was guided from distinct initial configurations to a designated equilibrium set-point. The performance of the NMPC schemes was evaluated across four different initial conditions. In all cases, the controller successfully guided the system to the target equilibrium. The formulation on SE(3) effectively handled the singularities and discontinuities typically associated with Euler-angle representations. The ProVANT Simulator facilitated the initial tuning and thorough validation of the control strategy. Moreover, the controller consistently enforced the force constraints on the propellers, maintaining the applied thrust within the specified limits of 0 to 12.3 N, as illustrated in Figure 19.

4.3. Unmanned Aerial Manipulator

This section presents a case study using the ProVANT Simulator to conduct a HIL experiment on an Unmanned Aerial Manipulator (UAM), a system composed of a quadrotor UAV serially connected to a 3 DOF manipulator arm, as illustrated in Figure 20. The objective of the experiment was to tune, evaluate the real-time performance, and compare the nonlinear H and W control strategies. For a detailed description of the system modeling and control design, the reader is referred to [18]. The physical parameters of the UAM are listed in Table 3.
To emulate the grasping action, a custom Gazebo plugin was developed to simulate the behavior of an electromagnet. This plugin generates a virtual magnetic field capable of attracting and holding metallic objects when they are in close proximity. It continuously monitors the distance between the end-effector and the target object, and once the simulated end-effector reaches a predefined threshold, which was set to 1 mm in this experiment, the object is rigidly attached to the end-effector and treated as an additional load in the UAM structure. In addition to this grasping mechanism, the simulator includes plugins that model the aerodynamic ground effect produced by the UAV’s propellers, as well as friction forces acting on the manipulator’s joints, which are assumed disturbances for control design purposes.
Figure 21 shows the hardware components of the HIL framework and their connections, while Figure 22 shows the block diagram of the implemented software. The experiment was executed in asynchronous mode. The simulation server used in this case study is a general-purpose notebook computer equipped with an Intel Core i7 7500U processor, with two physical and four logical cores, running at 2.9 GHz, 16 GB of RAM, and a NVIDIA 920MX GPU. This computer runs the Ubuntu version 20.04 operational system and executes the software components of the ProVANT Simulator. The embedded system executes the software components of the controller, which is composed of a Raspberry Pi 3B+ SOC with a quadcore ARM Cortex-A53 processor running at 1.2 GHz, with 1 GB of RAM, and a VideoCore IV GPU. The embedded system and the simulation server communicate through a Local Area Network (LAN) connected by a 1 Gbps Ethernet switch, with fixed IP addresses 192.168.0.10 and 192.168.0.100, respectively. The controller is a ROS node implemented in the C++ programming language on the embedded system that communicates using ROS messages with the ProVANT Simulator. Gazebo was set up with the Open Dynamics Engine (ODE), considering a step time of 4 ms, and the controllers were executed with a sample time of 12 ms.
Two experiments were conducted, experiment A and B, each with distinct objectives. A video recording of the experiments is available in https://youtu.be/t1t6xB98pJ4.
Experiment A, adapted from the benchmark proposed in [19], was conducted in a simplified environment to facilitate the tuning of the control laws according to a specific performance index, enabling a clearer comparison between the nonlinear H and W controllers. In this experiment, ground effect and joint friction forces of the manipulator are neglected, since they represent unmodeled dynamics for the controllers.
The scenario for Experiment A is shown in Figure 23. The task consists of a sequence of five phases: the UAM starts at the origin, p F L 4 F I ( 1 ) = [ 0 0 0 ] T m, then lifts off to p F L 4 F I ( 2 ) = [ 0 0 h 1 ] T m, and proceeds to p F L 4 F I ( 3 ) = [ 0.9 d g o a l 0 h 1 ] T m. Next, it reaches the final target while fully extending its manipulator arm at p F L 4 F I ( 4 ) = [ d g o a l 0 h g o a l ] T m. Finally, it returns to p F L 4 F I ( 5 ) = [ d g o a l 0 h 1 ] T m. The experiments parameters are based on Table V of [19], with h 1 = 2 m, d g o a l = 2 m, and h g o a l = 1 m.
In contrast, Experiment B was designed to evaluate the controllers in a more realistic and challenging scenario, involving tasks commonly performed by UAMs. Additionally, it incorporates a plugin to emulate a northeasterly wind disturbance, applying 0.5 N drag force to the center of gravity of the quadrotor UAV when operating outdoors (on the right side of the simulation environment). Experiment B aims to evaluate the following aspects of the UAM’s performance: (i) stable hovering capability; (ii) ability to follow a time-varying trajectory, grasp, and transport an object; (iii) dynamic response under manipulator arm movements; and (iv) robustness to disturbances such as ground effect, environmental wind, joint friction, and both parametric and structural uncertainties.
Figure 24 illustrates the simulation environment for Experiment B, indicating the UAM initial position, a static obstacle to be avoided, and a yellow metallic cube representing the target object. In this experiment, the UAM performs a mission composed of several phases, as illustrated in the Figure 25: the UAM starts from the initial position p F L 4 F I ( 0 ) = [ 0.5 2.7 0 ] T m, displaced from the first way point p F L 4 F I ( 1 ) = [ 0.5 2.7 1 ] T m, with all other states initialized to zero; goes through the intermediate point p F L 4 F I ( 2 ) = [ 1.5 1.5 1.1 ] T m; proceeds to the target position p F L 4 F I ( 3 ) = [ 2.23 2.7 0.73 ] T m where it hovers and fully extends its manipulator arm; it grasps a 200 g metallic cube; retracts the manipulator; returns to the starting position while carrying the object; and completes the mission with a landing.
The position, velocity and acceleration references used in all experiments were generated offline using a modified version of the Rapidly-exploring Random Tree (RRT*) algorithm [20]. This planning algorithm was executed through MoveIt (MoveIt 1.0 is a ROS-Based framework that provides access to various motion planning algorithms and essential functionalities such as collision detection [21]), a ROS application designed for robotic motion planning. The resulting reference trajectories were exported to a CSV file and subsequently used during the simulation runs. The values observed during the HIL experiments of the UAM DOFs, control efforts, and of the control execution times are, respectively, shown in Figure 26, Figure 27 and Figure 28.
In this case study, the ProVANT Simulator has demonstrated its value beyond serving as a platform for testing real-time performance of control strategies in complex systems through HIL experiments. It proved capable of emulating realistic operating conditions, enabling comprehensive evaluation of controller robustness. Moreover, it facilitated comparative analyses between different control strategies, supporting control engineers in selecting the most suitable approach to achieve specific performance goals.

4.4. ProVANT UAV 2 for Load Transportation

This section presents case studies involving the ProVANT UAV 2, a tilt-rotor unmanned aerial vehicle designed to perform load transportation missions, as illustrated in Figure 29. This UAV can be modeled as a mechanical system composed of four key rigid bodies: (i) the main UAV body, which includes batteries, electronics, ABS structure, and landing gear; (ii) the right thruster group, consisting of the right thruster and a revolute joint; (iii) the left thruster group, comprising the left thruster and a revolute joint; and (iv) the suspended load group, which includes the payload and the cable. Table 4 presents the physical parameters employed in the ProVANT Simulator. The following modeling assumptions are considered:
  • The cable is rigid and massless.
  • The center of mass of the main body does not align with the aircraft’s geometric center.
  • The attachment point of the cable is offset from both the main body’s geometric center and center of mass.
  • The centers of mass of the thruster groups are displaced from their respective tilting axes.

4.4.1. Trajectory Tracking of the Load with State Estimation

We first describe a case study involving load transportation by the ProVANT UAV 2, focusing on robust trajectory tracking of the suspended load while stabilizing the tilt-rotor UAV. The desired load trajectory, denoted as ( x tr ( t ) , y tr ( t ) , z tr ( t ) ) , comprises various connected paths, including vertical take-off in spiral, lateral and longitudinal flight under exogenous forces, and landing, as detailed in Table 5. For a detailed description of the control strategy and theoretical formulation, the reader is referred to [22].
In this case study, the state variables are estimated using data from multiple simulated sensors mounted on the UAV, each operating at distinct sampling rates. These include a GPS, barometer, IMU, camera, and position and velocity feedback from the servomotors in the tilting mechanisms. The parameters of the simulated sensors are summarized in Table 6. Environmental wind gusts are emulated by a force plugin that applies exogenous disturbances directly to the load during the simulation. The ProVANT simulator is employed to perform a synchronous SIL experiment that is carried out using the ODE physics engine.
Figure 30 illustrates the block diagram of the control architecture. A video demonstration of this experiment is available at https://youtu.be/um4XYFRk1CM. The outcomes of the SIL experiment are presented in Figure 31, Figure 32 and Figure 33.
In this case study, the ProVANT Simulator has been demonstrated to be a suitable environment for testing both control and state estimation algorithms in scenarios where onboard sensors operate at different sampling rates. It enabled the verification of correct algorithm implementation and facilitated the evaluation of the control strategy’s robustness under realistically emulated flight conditions.

4.4.2. Trajectory Tracking of the Load Using Hardware-in-the-Loop Simulation

In this case study, the ProVANT Simulator is integrated into an asynchronous HIL simulation framework to evaluate the performance and real-time feasibility of the explicit tube-based Model Predictive Control (MPC) proposed in [23].
In the control strategy, the MPC control law is precomputed offline via multi-parametric optimization, yielding a piecewise-affine policy over critical regions of the state space. At runtime, the controller identifies the region containing the current state and applies the associated affine law—avoiding online optimization and substantially reducing latency to meet real-time embedded requirements. A robust tube-based structure supplements this scheme with a secondary feedback correction derived from linear matrix inequalities (LMIs) and a robust positively invariant set for the uncertain linear parameter varying (LPV) model, compensating for model mismatch and disturbances while ensuring constraint satisfaction and robust stability.
The experimental setup consists of an NVIDIA Jetson embedded computer interfaced with the ProVANT Simulator via serial communication for the exchange of state information and control signals, as illustrated in Figure 34. The results of the HIL simulations are presented in Figure 35, Figure 36 and Figure 37. A video recording of the experiments is available at https://youtu.be/7hwKO6-Emjw. Detailed measurements of the execution time of the explicit tube-based MPC can be found in [23].
To conclude this case study, the ProVANT Simulator enabled precise measurement of the control algorithm’s execution time on the embedded platform, as presented in Figure 38, allowing for the assessment of its compliance with real-time constraints and demonstrating that the controller is ready for deployment on the physical prototype.

4.5. ProVANT UAV 3

This subsection presents a case study involving the ProVANT UAV 3, illustrated in Figure 39. This UAV is composed of: (i) the fuselage, where electronic components such as the battery, sensors, microprocessors, and other equipment are assembled; (ii) the thruster groups, which consist of propellers, brushless DC motors, and servomotors responsible for tilting the propellers; and (iii) the tail surfaces, comprising horizontal and vertical stabilizers, the former generating pitch moments via elevator deflection and the latter generating yaw moments via rudder deflection.
The ProVANT UAV 3, along with the UAVs presented in the subsequent case studies, are convertible platforms capable of transitioning between helicopter and cruise flight modes. These platforms require the integration of aerodynamic models to accurately represent their behavior. Designing control laws for such UAVs is particularly challenging due to the varying effects of relative wind across flight modes. In helicopter mode (VTOL and hovering), the low relative wind results in small aerodynamic forces. In contrast, during cruise flight, higher wind speeds enable small control surface deflections to generate significant forces and moments for effective navigation [24]. Classical linear controllers are typically inadequate to guarantee acceptable trajectory tracking performance across the full flight envelope.
The ProVANT UAV 3 features tail-surfaces that enhance the forward flight performance by improving trim stability. However, its thruster groups remain essential for both longitudinal and directional control, even in cruise flight, since the UAV lacks fixed-wing and, thereby, cannot fully transition the rotors to the horizontal position. As a result, the aircraft operates in a continuous transition/cruise mode. Its flight envelope includes vertical take-off, axial flight, hovering, transition to cruise flight at constant altitude, longitudinal plane maneuvers (movement in the x-z plane), lateral-directional plane maneuvers (movement in the x-y plane), transition from cruise to hovering, and vertical landing.
The mechanical design of the ProVANT UAV 3 was developed using SolidWorks 2024 and exported to the ProVANT simulator. The fuselage features a teardrop shape to reduce drag and enhance aerodynamic efficiency. Tail surfaces were inspired by the XV-15 aircraft, employing NACA 0009 and NACA 64A015 profiles for the vertical and horizontal stabilizers, respectively. Due to Gazebo’s lack of support for electronics and fluid dynamics simulation, the electrical dynamics of the brushless motors were assumed sufficiently fast to be neglected. Nonlinear aerodynamic coefficients for the tail surfaces were obtained from [25], while the symmetric fuselage was modeled as a symmetrical airfoil, using data from [26]. Linear interpolation was applied to all aerodynamic coefficient data to ensure smooth behavior. The simulation was through the ODE physics engine, configured with a step time of 4 ms and a controller sample time of 12 ms. Table 7 presents the parameters of the ProVANT UAV 3.
In this case study, the ProVANT Simulator is employed to conduct synchronous SIL experiment evaluating the performance of the Robust Adaptive Mixing Controller (RAMC) proposed in [27]. A comprehensive discussion of the UAV’s mathematical modeling and control design can be found in the same reference. The RAMC controller adopts a cascade structure, with the outer loop responsible for planar motion, governed by the x and y dynamics, and the inner loop handling altitude and attitude control, which includes the dynamics of z, ϕ , θ , ψ , α R f , α L f , α L b , α R b , and the UAV body velocities. The outer loop kinematic controller generates desired linear velocity references, which are then tracked by the inner loop RAMC. A block diagram of the proposed control architecture is shown in Figure 40.
The experiment was executed on a general-purpose notebook equipped with an Intel Core i7 8750H processor (2.2 GHz), featuring six physical cores, twelve logical threads, 24 GB of RAM, and an NVIDIA GTX 1050Ti GPU, running Ubuntu Linux version 18.04. The implemented control strategy combines pre-designed linear controllers to achieve stable trajectory tracking across the entire flight envelope of the ProVANT UAV 3 while mitigating the effects of external disturbances.
The SIL experiment evaluates the UAV’s ability to follow a predefined trajectory composed of six distinct segments, as detailed in Figure 41. Accordingly, Figure 42 and Figure 43 show the time evolution of the translational position, attitude, tilt angles, applied forces and torques, and the deflections of the aerodynamic control surfaces. A video recording of the simulation is available at https://youtu.be/Lrf-QX34Wnk.
To conclude, the experimental results indicate that the ProVANT Simulator effectively emulated the behavior of the tilt-rotor UAV during the transition maneuver, clearly demonstrating that this operation would not be feasible without aerodynamic tail surfaces (as shown in the experiment video). Additionally, it enabled a thorough evaluation of the control strategy’s robustness under realistic flight conditions and provided evidence for the adequacy of the mathematical model employed in the controller’s design in capturing the aircraft’s dynamic behavior.

4.6. ProVANT EMERGENTIA UAV

This section presents a case study involving the ProVANT EMERGENTIA, illustrated in Figure 44. Unlike the ProVANT UAV 3, the ProVANT EMERGENTIA model features fixed wings and V-tail surfaces. During cruise flight, the wings generate significant aerodynamic lift to support sustained forward motion, allowing the rotors to be tilted horizontally and enabling the aircraft to operate in airplane mode. For further details on the proposed mathematical modeling and control law design, please refer to [28].
The ProVANT EMERGENTIA mechanical design was developed using Computer-Aided Three-dimensional Interactive Application (CATIA) V5 software and subsequently exported to the ProVANT Simulator. Wind tunnel experiments were conducted to determine the aerodynamic coefficients used to calculate the forces and moments generated by aerodynamic surfaces, including the propellers, fuselage, wings, tail surfaces, and aerodynamic interactions among these surfaces [29]. Table 8 presents the UAV parameters.
The ProVANT Simulator was employed to perform synchronous SIL experiments aiming at evaluating the effectiveness of a robust nonlinear W controller addressed in [28]. This controller is a single-layer nonlinear robust optimal control strategy (see Figure 45) designed to achieve accurate trajectory tracking across the entire flight envelope of the ProVANT EMERGENTIA, while mitigating the effects of external disturbances. To conduct the experiment, Gazebo was set up with the ODE physics engine using a simulation time step of 4 ms, while the control algorithm was executed with a sample time of 12 ms. The SIL experiment was conducted on a general-purpose notebook with an Intel Core i7 8750H processor (2.2 GHz), featuring six physical cores and twelve logical threads, 24 GB of RAM, and an NVIDIA GTX 1050Ti GPU, running Ubuntu Linux version 18.04.
In the SIL experiment, the ProVANT EMERGENTIA is tasked with following a predefined trajectory composed of six distinct segments, as illustrated in Figure 46. In the first segment, the UAV must take-off from a home position while accelerating forward. In the second segment, it reaches the cruise speed (33 m/s) and performs steady forward flight at constant altitude. The third segment involves flying along a circular path while maintaining both altitude and cruise speed. Upon completing this turn, the UAV performs straight-level flight. In the fifth and sixth segments, it decelerates and performs a landing maneuver at the final destination, where it remains stationary. A video recording of the experiments is available at https://youtu.be/6P3yH5hxEaY.
During the experiment, external disturbances and wind gusts were applied at critical moments, specifically during the transitions from helicopter to cruise flight mode at the beginning, and from cruise back to helicopter mode at the end. As can be observed from Figure 46 and Figure 47, the control system successfully attenuated all of these disturbances. To execute the circular segment of the trajectory, the tilt-rotor UAV adopted a non-zero roll angle, a necessary physical condition to generate lateral lift and enable coordinated turning. Additionally, the system exhibited a yaw deviation due to lateral wind, reflecting realistic aerodynamic behavior. It is noteworthy that, due to the high magnitude of the relative wind speed during cruise flight, the propellers lost efficiency, requiring a higher angular velocity, as shown in Figure 48. These results confirm that the ProVANT simulator closely replicates the dynamic responses expected under real-world flight conditions.

4.7. VERSATILE UAV

This section presents a case study involving the VERSATILE UAV, a quadtilt-rotor aircraft depicted in Figure 49. Unlike the ProVANT EMERGENTIA, this configuration features four independently controlled propulsion groups. This capability enables the generation of greater yaw and pitch torques, which enhances the aircraft’s maneuverability at low speeds when compared to the ProVANT EMERGENTIA UAV, as discussed in [30].
This case study aims to evaluate the stability and trajectory tracking performance of the VERSATILE UAV across its entire flight envelope under external disturbances, using a set of control strategies. To this end, five RAMC controllers, based on the same architecture, presented in Section 4.5 and illustrated in Figure 40, were implemented and tested: RAMC FL H , RAMC FL H 2 / H , RAMC PDC H , RAMC VL H , and RAMC VL H 2 / H . Each controller adopts a distinct design methodology to compute the mixing feedback gains used in the adaptive structure of the dynamic controller. A detailed discussion of their theoretical foundations and implementation procedures is provided in [31]. Table 9 presents the VERSATILE UAV parameters.
Asynchronous HIL experiments were conducted using the ProVANT Simulator to evaluate the controllers’ real-time performance and assess their readiness for deployment on the physical prototype. The ODE physics engine was chosen in Gazebo to experiment, taking into consideration a time step of 4 ms and a sample time of 12 ms for the controller, the latter representing the system’s real-time constraint. The control algorithm was executed in a Raspberry Pi 4 model B SBS with a quadcore ARM Cortex-A72 processor running at 1.5 GHz, with 8GB of DDR4 RAM and a VideoCore XI GPU (ARM Holdings, Cambridge, UK). The UAV was tasked with tracking the same trajectory addressed in the previous case study. The results of the HIL simulations are illustrated in Figure 50, Figure 51, Figure 52 and Figure 53, and a video of the experiments is available at https://youtu.be/GxHePSJiPKg. A histogram of the execution times for the implemented control strategies is presented in Figure 53. As shown, all strategies successfully met the real-time performance requirement.
By offering a realistic, high-fidelity simulation environment, the ProVANT Simulator enabled rigorous testing and evaluation of various controllers, clearly exposing cases where non-robust strategies failed to maintain trajectory tracking under adverse conditions. These results highlight the simulator’s effectiveness as a valuable tool for assessing the robustness of control strategies.

5. Conclusions

The ProVANT Simulator was designed as a versatile platform to support research and development of UAV control algorithms. It provides an accurate representation of complex UAV dynamics, enabling the evaluation of control strategy performance across different scenarios. Through integration with established tools such as Gazebo and ROS, the simulator offers a modular, user-friendly environment for high-fidelity simulation-based testing, including SIL and HIL experiments.
This work presented the results of several case studies conducted using the ProVANT Simulator, featuring different UAV configurations, including quadrotors and tilt-rotors. The scenarios encompassed a range of tasks, such as aggressive maneuvers, load transportation, and transitions between helicopter and airplane flight modes. These case studies demonstrated the simulator’s ability to accurately emulate complex robotic systems and underscored its potential for validating control strategies before conducting real-world flight experiments.
Future developments will concentrate on improving the platform’s usability and extending its capabilities to include the simultaneous simulation of multi-UAV systems, along with the integration of more accurate environmental wind models. Furthermore, models for battery and drive unit power consumption are already planned and are currently under development. The UAVs featured in the case studies are currently under construction at the Federal University of Minas Gerais and the University of Seville. Data collected from upcoming real-flight experiments will be used to enhance the simulator’s fidelity. These advancements will reduce the gap between simulation and real-world UAV applications, further establishing the ProVANT simulator as a valuable resource for the aerospace, robotics, and control systems community.

Author Contributions

Conceptualization, J.E.M., D.N.C., B.S.R., R.A., I.B.P.N., J.C.P., M.A.S., L.B.B., S.E. and G.V.R.; Methodology, J.E.M., D.N.C., J.M.C., B.S.R., R.A., I.B.P.N., J.C.P., M.A.S. and G.V.R.; Software, J.E.M., D.N.C., J.M.C., B.S.R., R.A., I.B.P.N., J.C.P., D.F.S. and M.A.S.; Validation, J.E.M., D.N.C., J.M.C., B.S.R., R.A., I.B.P.N., J.C.P. and D.F.S.; Formal analysis, J.E.M., D.N.C., J.M.C., B.S.R., R.A., I.B.P.N., J.C.P., D.F.S. and M.A.S.; Investigation, J.E.M., D.N.C., J.M.C., B.S.R., R.A., I.B.P.N., J.C.P., M.A.S., S.E. and G.V.R.; Resources, J.E.M., D.N.C., B.S.R., R.A., I.B.P.N., J.C.P. and G.V.R.; Data curation, J.E.M., D.N.C., J.M.C., B.S.R., R.A., I.B.P.N., J.C.P. and G.V.R.; Writing—original draft, J.E.M., D.N.C., J.M.C., B.S.R., R.A., I.B.P.N., J.C.P., D.F.S. and G.V.R.; Writing—review and editing, J.E.M., D.N.C., B.S.R., M.A.S., L.B.B., S.E. and G.V.R.; Visualization, J.E.M., D.N.C., B.S.R., M.A.S. and G.V.R.; Supervision, D.N.C., L.B.B., S.E. and G.V.R.; Project administration, L.B.B., S.E. and G.V.R.; Funding acquisition, G.V.R. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the Brazilian agencies Coordenação de Aperfeiçoamento de Pessoal de Nível Superior (CAPES)—Finance Code 001—through the Academic Excellence Program (PROEX), National Council for Scientific and Technological Development (CNPq) under the grants 317058/2023-1 and 422143/2023-5, and Research Foundation of Minas Gerais (FAPEMIG) under the grant BPD-00960-22.

Data Availability Statement

The original data presented in the study are openly available in the GitHub Repository https://github.com/ProVANT-Project.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Agüero, C.E.; Koenig, N.; Chen, I.; Boyer, H.; Peters, S.; Hsu, J.; Gerkey, B.; Paepcke, S.; Rivero, J.L.; Manzo, J.; et al. Inside the virtual robotics challenge: Simulating real-time robotic disaster response. IEEE Trans. Autom. Sci. Eng. 2015, 12, 494–506. [Google Scholar] [CrossRef]
  2. Hambuchen, K.A.; Roman, M.C.; Sivak, A.; Herblet, A.; Koenig, N.; Newmyer, D.; Ambrose, R. Nasa’s space robotics challenge: Advancing robotics for future exploration missions. In Proceedings of the AIAA SPACE and Astronautics Forum and Exposition, Orlando, FL, USA, 12–14 September 2017; p. 5120. [Google Scholar]
  3. Koval, A.; Kanellakis, C.; Vidmark, E.; Haluska, J.; Nikolakopoulos, G. A subterranean virtual cave world for gazebo based on the DARPA SubT challenge. arXiv 2020, arXiv:2004.08452. [Google Scholar] [CrossRef]
  4. Pizetta, I.H.B.; Brandão, A.S.; Sarcinelli-Filho, M. A Hardware-in-the-Loop Platform for Rotary-Wing Unmanned Aerial Vehicles. J. Intell. Robot. Syst. 2016, 84, 725–743. [Google Scholar] [CrossRef]
  5. Furrer, F.; Burri, M.; Achtelik, M.; Siegwart, R. RotorS—A Modular Gazebo MAV Simulator Framework; Springer: Berlin/Heidelberg, Germany, 2016; Volume 625, pp. 595–625. [Google Scholar] [CrossRef]
  6. Koubâa, A.; Allouch, A.; Alajlan, M.; Javed, Y.; Belghith, A.; Khalgui, M. Micro Air Vehicle Link (MAVlink) in a Nutshell: A Survey. IEEE Access 2019, 7, 87658–87680. [Google Scholar] [CrossRef]
  7. Chitta, S.; Marder-Eppstein, E.; Meeussen, W.; Pradeep, V.; Tsouroukdissian, A.R.; Bohren, J.; Coleman, D.; Magyar, B.; Raiola, G.; Lüdtke, M.; et al. ros_control: A generic and simple control framework for ROS. J. Open Source Softw. 2017, 2, 456. [Google Scholar] [CrossRef]
  8. Dimmig, C.A.; Silano, G.; McGuire, K.; Gabellieri, C.; Hönig, W.; Moore, J.; Kobilarov, M. Survey of Simulators for Aerial Robots: An Overview and In-Depth Systematic Comparisons. IEEE Robot. Autom. Mag. 2024, 32, 2–15. [Google Scholar] [CrossRef]
  9. Hentati, A.I.; Krichen, L.; Fourati, M.; Fourati, L.C. Simulation Tools, Environments and Frameworks for UAV Systems Performance Analysis. In Proceedings of the 14th International Wireless Communications & Mobile Computing Conference, Limassol, Cyprus, 25–29 June 2018; pp. 1495–1500. [Google Scholar] [CrossRef]
  10. Xie, D.; Hu, R.; Wang, C.; Zhu, C.; Xu, H.; Li, Q. A Simulation Framework of Unmanned Aerial Vehicles Route Planning Design and Validation for Landslide Monitoring. Remote Sens. 2023, 15, 5758. [Google Scholar] [CrossRef]
  11. Gill, J.S.; Saeedi Velashani, M.; Wolf, J.; Kenney, J.; Manesh, M.R.; Kaabouch, N. Simulation Testbeds and Frameworks for UAV Performance Evaluation. In Proceedings of the IEEE International Conference on Electro Information Technology, Mount Pleasant, MI, USA, 14–15 May 2021; pp. 335–341. [Google Scholar] [CrossRef]
  12. Koenig, N.; Howard, A. Design and use paradigms for gazebo, an open-source multi-robot simulator. In Proceedings of the 2004 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS) (IEEE Cat. No.04CH37566), Sendai, Japan, 28 September–2 October 2004; Volume 3, pp. 2149–2154. [Google Scholar]
  13. Koubaa, A. Robot Operating System (ROS): The Complete Reference (Volume 2), 1st ed.; Springer: Berlin/Heidelberg, Germany, 2017. [Google Scholar]
  14. Nascimento, I.B.P. Nonlinear Model Predictive Control Strategies for Autonomous Vehicles in Unknown Environments. Master’s Thesis, Federal University of Minas Gerais, Belo Horizonte, Brazil, 2020. [Google Scholar]
  15. Raffo, G.V. Robust Control Strategies for a Quadrotor Helicopter: An Underactuated Mechanical System. Ph.D. Thesis, Universid de Sevilha, Seville, Spain, 2011. [Google Scholar]
  16. Andersson, J.A.; Gillis, J.; Horn, G.; Rawlings, J.B.; Diehl, M. CasADi: A Software Framework for Nonlinear Optimization and Optimal Control. Math. Program. Comput. 2019, 11, 1–36. [Google Scholar] [CrossRef]
  17. Pereira, J.C.; Leite, V.J.S.; Raffo, G.V. Stabilizing NMPC Approaches for Underactuated Mechanical Systems on the SE(3) Manifold. arXiv 2025, arXiv:2503.17458. [Google Scholar] [CrossRef]
  18. de Morais, J.E.; Cardoso, D.N.; Raffo, G.V. Robust Nonlinear Control of Aerial Manipulators. J. Control. Autom. Electr. Syst. 2023, 34, 1–17. [Google Scholar] [CrossRef]
  19. Suarez, A.; Vega, V.M.; Fernandez, M.; Heredia, G.; Ollero, A. Benchmarks for Aerial Manipulation. IEEE Robot. Autom. Lett. 2020, 5, 2650–2657. [Google Scholar] [CrossRef]
  20. Choset, H.; Lynch, K.; Hutchinson, S.; Kantor, G.; Burgard, W.; Kavraki, L.; Thrun, S. Principles of Robot Motion: Theory, Algorithms, and Implementations; MIT Press: Cambridge, UK, 2005; p. 603. [Google Scholar]
  21. Coleman, D.; Sucan, I.; Chitta, S.; Correll, N. Reducing the Barrier to Entry of Complex Robotic Software: A MoveIt! Case Study. J. Softw. Eng. Robot. 2014, 1, 1–14. [Google Scholar]
  22. Rego, B.S.; Raimondo, D.M.; Raffo, G.V. Path Tracking Control with State Estimation based on Constrained Zonotopes for Aerial Load Transportation. In Proceedings of the 57th IEEE Conference on Decision and Control, Miami, FL, USA, 17–19 December 2018; pp. 1979–1984. [Google Scholar]
  23. Andrade, R.; Ferramosca, A.; Normey-Rico, J.E.; Raffo, G.V. Tube-Based Explicit Model Predictive Control for a Tiltrotor UAV in Cargo Transportation Tasks. J. Control. Autom. Electr. Syst. 2024, 35, 1039–1058. [Google Scholar] [CrossRef]
  24. Morin, P. Modeling and control of convertible Micro Air Vehicles. In Proceedings of the Robot Motion and Control (RoMoCo), 2015 10th International Workshop on IEEE, Poznan, Poland, 6–8 July 2015; pp. 188–198. [Google Scholar]
  25. Ferguson, S.W. A Mathematical Model for Real Time Flight Simulation of a Generic Tilt-Rotor Aircraft. NASA CR-166536. 1988. Available online: https://rotorcraft.arc.nasa.gov/Publications/files/CR-166536_882.pdf (accessed on 30 June 2025).
  26. Sheldahl, R.E.; Klimas, P.C. Aerodynamic Characteristics of Seven Symmetrical Airfoil Sections Through 180-Degree Angle of Attack for Use in Aerodynamic Analysis of Vertical Axis Wind Turbines; Technical Report; Sandia National Labs.: Albuquerque, NM, USA, 1981. [Google Scholar]
  27. Cardoso, D.N.; Esteban, S.; Raffo, G.V. A new robust adaptive mixing control for trajectory tracking with improved forward flight of a tilt-rotor UAV. ISA Trans. 2021, 110, 86–104. [Google Scholar] [CrossRef] [PubMed]
  28. Cardoso, D.N. Robust Control Framework in the Weighted Sobolev Space. Ph.D. Thesis, Universidade Federal de Minas Gerais, Belo Horizonte, Brazil, 2021. [Google Scholar]
  29. Ortega, F.J.; Nunez, M.; Esteban, S. Aerodynamics and Propulsive Modeling of a Bi-Rotor Convertible Aircraft for the Identification of Trim Conditions in Longitudinal Flight. In Proceedings of the Vertical Flight Society’s 77th Annual Forum & Technology Display (VFS2021), Virtual, 10–14 May 2021; pp. 1–15. [Google Scholar]
  30. Allenspach, M.; Ducard, G.J.J. Nonlinear model predictive control and guidance for a propeller-tilting hybrid unmanned air vehicle. Automatica 2021, 132, 109790. [Google Scholar] [CrossRef]
  31. Campos, J.M.; Cardoso, D.N.; Esteban, S.; Raffo, G.V. Enhanced robust adaptive flight control for a convertible VTOL UAV. J. Frankl. Inst. 2024, 361, 106663. [Google Scholar] [CrossRef]
Figure 1. Overview of the ProVANT Simulator software architecture.
Figure 1. Overview of the ProVANT Simulator software architecture.
Aerospace 12 00762 g001
Figure 2. Containers representing the internal elements of the ProVANT Simulator.
Figure 2. Containers representing the internal elements of the ProVANT Simulator.
Aerospace 12 00762 g002
Figure 3. Internal elements of the Controller container.
Figure 3. Internal elements of the Controller container.
Aerospace 12 00762 g003
Figure 4. Control strategy UML class diagram.
Figure 4. Control strategy UML class diagram.
Aerospace 12 00762 g004
Figure 5. Graphical user interface–main window.
Figure 5. Graphical user interface–main window.
Aerospace 12 00762 g005
Figure 6. Graphical user interface–Controller tab.
Figure 6. Graphical user interface–Controller tab.
Aerospace 12 00762 g006
Figure 7. General structure of asynchronous HIL mode.
Figure 7. General structure of asynchronous HIL mode.
Aerospace 12 00762 g007
Figure 8. General structure of the synchronous HIL mode.
Figure 8. General structure of the synchronous HIL mode.
Aerospace 12 00762 g008
Figure 9. Diagram of the ProVANT Simulator execution and flow of data using a controller written in MATLAB R2024b script using the MATLAB Engine API for C++.
Figure 9. Diagram of the ProVANT Simulator execution and flow of data using a controller written in MATLAB R2024b script using the MATLAB Engine API for C++.
Aerospace 12 00762 g009
Figure 10. Block diagram illustrating the NMPC control strategy utilized in the SIL experiment.
Figure 10. Block diagram illustrating the NMPC control strategy utilized in the SIL experiment.
Aerospace 12 00762 g010
Figure 11. Three-dimensional view of the trajectory (yellow line) traversed by the quadrotor UAV while avoiding three obstacles in an urban-like environment. The green and red circles correspond to the initial position of the quadrotor UAV and the desired target, respectively. This result corresponds to the case study in Section 4.1.
Figure 11. Three-dimensional view of the trajectory (yellow line) traversed by the quadrotor UAV while avoiding three obstacles in an urban-like environment. The green and red circles correspond to the initial position of the quadrotor UAV and the desired target, respectively. This result corresponds to the case study in Section 4.1.
Aerospace 12 00762 g011
Figure 12. Time evolution of the UAV’s position (x, y, z) and linear velocities ( x ˙ , y ˙ , z ˙ ) obtained from the SIL experiment.
Figure 12. Time evolution of the UAV’s position (x, y, z) and linear velocities ( x ˙ , y ˙ , z ˙ ) obtained from the SIL experiment.
Aerospace 12 00762 g012
Figure 13. Time evolution of the UAV’s attitude angles roll ( ϕ ) pitch ( θ ) and yaw ( ψ ) expressed in Euler angles using the ZYX convention about local axes, and their time derivatives ( ϕ ˙ , θ ˙ , ϕ ˙ ) obtained from the SIL experiment.
Figure 13. Time evolution of the UAV’s attitude angles roll ( ϕ ) pitch ( θ ) and yaw ( ψ ) expressed in Euler angles using the ZYX convention about local axes, and their time derivatives ( ϕ ˙ , θ ˙ , ϕ ˙ ) obtained from the SIL experiment.
Aerospace 12 00762 g013
Figure 14. Time evolution of the thrust forces applied to the quadrotor UAV rotors during the SIL experiment.
Figure 14. Time evolution of the thrust forces applied to the quadrotor UAV rotors during the SIL experiment.
Aerospace 12 00762 g014
Figure 15. Block diagram of the NMPC scheme implemented for the ProVANT quadrotor UAV to enable aggressive maneuvering.
Figure 15. Block diagram of the NMPC scheme implemented for the ProVANT quadrotor UAV to enable aggressive maneuvering.
Aerospace 12 00762 g015
Figure 16. Quadrotor UAV successfully recovering from an upside-down configuration.
Figure 16. Quadrotor UAV successfully recovering from an upside-down configuration.
Aerospace 12 00762 g016
Figure 17. 3D visualization of the quadrotor UAV performing aggressive maneuvers under SIL simulation. The UAV is represented by a body-fixed reference frame, with axes colored as follows: red for the x-axis, green for the y-axis, and blue for the z-axis. The trajectories correspond to different initial conditions, labeled as x 01 , x 02 , x 03 , and x 04 . This result corresponds to the case study in Section 4.2.
Figure 17. 3D visualization of the quadrotor UAV performing aggressive maneuvers under SIL simulation. The UAV is represented by a body-fixed reference frame, with axes colored as follows: red for the x-axis, green for the y-axis, and blue for the z-axis. The trajectories correspond to different initial conditions, labeled as x 01 , x 02 , x 03 , and x 04 . This result corresponds to the case study in Section 4.2.
Aerospace 12 00762 g017
Figure 18. Translational positions (x, y, z), attitude angles roll ( ϕ ), pitch ( θ ), and yaw ( ψ ) expressed in Euler angles using the ZYX convention about the local axes and their time derivatives, along with the linear velocities, obtained from the SIL experiment. This result corresponds to the case study in Section 4.2.
Figure 18. Translational positions (x, y, z), attitude angles roll ( ϕ ), pitch ( θ ), and yaw ( ψ ) expressed in Euler angles using the ZYX convention about the local axes and their time derivatives, along with the linear velocities, obtained from the SIL experiment. This result corresponds to the case study in Section 4.2.
Aerospace 12 00762 g018
Figure 19. Measured UAV propeller thrusts during aggressive motion control. The results confirm that the NMPC controller ensures compliance with the actuator limits, bounded between 0 and 12.3 N. This result corresponds to the case study in Section 4.2.
Figure 19. Measured UAV propeller thrusts during aggressive motion control. The results confirm that the NMPC controller ensures compliance with the actuator limits, bounded between 0 and 12.3 N. This result corresponds to the case study in Section 4.2.
Aerospace 12 00762 g019
Figure 20. The UAM mechanical design. In the illustration, ( f 1 , f 2 , f 3 , f 4 ) represent the forces generated by each propeller, while ( β 1 , β 2 , β 3 ) denote the angular positions of the servo motors. The distances between joint axes are indicated by ( a 1 ; a 2 ; a 3 ); l represents the distance from the UAV’s origin to each propeller; l 0 is the distance from the UAV’s origin to the center of the first manipulator joint; (x, y, z) correspond to the translational positions, and ( ϕ , θ , ψ ) denote the end-effector’s orientation using Euler angles with a ZYX rotation sequence about the local axes.
Figure 20. The UAM mechanical design. In the illustration, ( f 1 , f 2 , f 3 , f 4 ) represent the forces generated by each propeller, while ( β 1 , β 2 , β 3 ) denote the angular positions of the servo motors. The distances between joint axes are indicated by ( a 1 ; a 2 ; a 3 ); l represents the distance from the UAV’s origin to each propeller; l 0 is the distance from the UAV’s origin to the center of the first manipulator joint; (x, y, z) correspond to the translational positions, and ( ϕ , θ , ψ ) denote the end-effector’s orientation using Euler angles with a ZYX rotation sequence about the local axes.
Aerospace 12 00762 g020
Figure 21. Connection between the embedded system and the simulation server, the software running in each system component, and the data transmitted between the software.
Figure 21. Connection between the embedded system and the simulation server, the software running in each system component, and the data transmitted between the software.
Aerospace 12 00762 g021
Figure 22. Block diagram illustrating the control strategies implemented for the UAM during the HIL experiments.
Figure 22. Block diagram illustrating the control strategies implemented for the UAM during the HIL experiments.
Aerospace 12 00762 g022
Figure 23. Environment of the Experiment A. Image obtained from [19].
Figure 23. Environment of the Experiment A. Image obtained from [19].
Aerospace 12 00762 g023
Figure 24. Simulation environment designed in Gazebo for Experiment B.
Figure 24. Simulation environment designed in Gazebo for Experiment B.
Aerospace 12 00762 g024
Figure 25. 3D trajectory of UAM end-effector during the HIL experiment. The red triangle indicates the point where the H IADu control failed and the UAM falls to the ground.
Figure 25. 3D trajectory of UAM end-effector during the HIL experiment. The red triangle indicates the point where the H IADu control failed and the UAM falls to the ground.
Aerospace 12 00762 g025
Figure 26. Roll ( ϕ ) and pitch ( θ ) angles, error of the yaw ( ψ ˜ ) angle, error of the translational positions ( x ˜ , y ˜ , z ˜ ) and angles of the manipulator arm ( β ˜ 1 , β ˜ 2 , β ˜ 3 ) during the HIL experiment. The red triangle indicates the point where the H IADu control failed and the UAM falls to the ground. This result corresponds to the case study in Section 4.3.
Figure 26. Roll ( ϕ ) and pitch ( θ ) angles, error of the yaw ( ψ ˜ ) angle, error of the translational positions ( x ˜ , y ˜ , z ˜ ) and angles of the manipulator arm ( β ˜ 1 , β ˜ 2 , β ˜ 3 ) during the HIL experiment. The red triangle indicates the point where the H IADu control failed and the UAM falls to the ground. This result corresponds to the case study in Section 4.3.
Aerospace 12 00762 g026
Figure 27. Applied control inputs during the HIL experiment. The purple line indicates the approximate instant in which the cube is grasped by the end-effector using the different controllers, and the red triangle indicates the point where the H IADu control failed and the UAM falls to the ground. This result corresponds to the case study in Section 4.3.
Figure 27. Applied control inputs during the HIL experiment. The purple line indicates the approximate instant in which the cube is grasped by the end-effector using the different controllers, and the red triangle indicates the point where the H IADu control failed and the UAM falls to the ground. This result corresponds to the case study in Section 4.3.
Aerospace 12 00762 g027
Figure 28. Control law execution time for the case study in Section 4.3.
Figure 28. Control law execution time for the case study in Section 4.3.
Aerospace 12 00762 g028
Figure 29. The ProVANT UAV 2 mechanical design.
Figure 29. The ProVANT UAV 2 mechanical design.
Aerospace 12 00762 g029
Figure 30. Block diagram illustrating the control strategy implemented for aerial load transportation with state estimation and simulated sensors used in [22].
Figure 30. Block diagram illustrating the control strategy implemented for aerial load transportation with state estimation and simulated sensors used in [22].
Aerospace 12 00762 g030
Figure 31. Trajectory tracking in the 3D view of the ProVANT UAV 2 for load transportation, resulting from the SIL experiment. This result corresponds to the case study in Section 4.4.1.
Figure 31. Trajectory tracking in the 3D view of the ProVANT UAV 2 for load transportation, resulting from the SIL experiment. This result corresponds to the case study in Section 4.4.1.
Aerospace 12 00762 g031
Figure 32. Translational positions (x, y, z), attitude angles roll ( ϕ ), pitch ( θ ), and yaw ( ψ ) expressed in Euler angles using the ZYX convention about the local axes, along with the tilting angles ( α R , α L ) of the right and left servomotors, and the load angles ( γ 1 , γ 2 ), obtained from the SIL experiment. This result corresponds to the case study in Section 4.4.1.
Figure 32. Translational positions (x, y, z), attitude angles roll ( ϕ ), pitch ( θ ), and yaw ( ψ ) expressed in Euler angles using the ZYX convention about the local axes, along with the tilting angles ( α R , α L ) of the right and left servomotors, and the load angles ( γ 1 , γ 2 ), obtained from the SIL experiment. This result corresponds to the case study in Section 4.4.1.
Aerospace 12 00762 g032
Figure 33. Forces generated by the propellers ( F R , F L ), torques applied to the thruster assemblies by the servomotors ( τ R , τ L ), and disturbance forces acting on the load along the x and y axes of the world frame ( d x , d y ), obtained from the SIL experiment. This result corresponds to the case study in Section 4.4.1.
Figure 33. Forces generated by the propellers ( F R , F L ), torques applied to the thruster assemblies by the servomotors ( τ R , τ L ), and disturbance forces acting on the load along the x and y axes of the world frame ( d x , d y ), obtained from the SIL experiment. This result corresponds to the case study in Section 4.4.1.
Aerospace 12 00762 g033
Figure 34. Block diagram illustrating the control strategy implemented for aerial load transportation using HIL experiment.
Figure 34. Block diagram illustrating the control strategy implemented for aerial load transportation using HIL experiment.
Aerospace 12 00762 g034
Figure 35. Trajectory tracking in the 3D view of the ProVANT UAV 2 for load transportation, resulting from the HIL experiment. This result corresponds to the case study in Section 4.4.2.
Figure 35. Trajectory tracking in the 3D view of the ProVANT UAV 2 for load transportation, resulting from the HIL experiment. This result corresponds to the case study in Section 4.4.2.
Aerospace 12 00762 g035
Figure 36. Translational positions (x, y, z), attitude angles roll ( ϕ ), pitch ( θ ), and yaw ( ψ ) expressed in Euler angles using the ZYX convention about the local axes, along with the tilting angles ( α R , α L ) of the right and left servomotors, and the load angles ( γ 1 , γ 2 ). This result corresponds to the case study in Section 4.4.2.
Figure 36. Translational positions (x, y, z), attitude angles roll ( ϕ ), pitch ( θ ), and yaw ( ψ ) expressed in Euler angles using the ZYX convention about the local axes, along with the tilting angles ( α R , α L ) of the right and left servomotors, and the load angles ( γ 1 , γ 2 ). This result corresponds to the case study in Section 4.4.2.
Aerospace 12 00762 g036
Figure 37. Forces generated by the propellers ( F R , F L ), torques applied to the thruster assemblies by the servomotors ( τ R , τ L ). This result corresponds to the case study in Section 4.4.2.
Figure 37. Forces generated by the propellers ( F R , F L ), torques applied to the thruster assemblies by the servomotors ( τ R , τ L ). This result corresponds to the case study in Section 4.4.2.
Aerospace 12 00762 g037
Figure 38. Control law execution time for the case study in Section 4.4.2.
Figure 38. Control law execution time for the case study in Section 4.4.2.
Aerospace 12 00762 g038
Figure 39. The ProVANT UAV 3 mechanical design.
Figure 39. The ProVANT UAV 3 mechanical design.
Aerospace 12 00762 g039
Figure 40. Block diagram of the control strategy proposed in [27], implemented for the ProVANT UAV 3. This strategy is designed to enable operation in both helicopter and transition flight modes.
Figure 40. Block diagram of the control strategy proposed in [27], implemented for the ProVANT UAV 3. This strategy is designed to enable operation in both helicopter and transition flight modes.
Aerospace 12 00762 g040
Figure 41. Trajectory tracking in the 3D view of ProVANT UAV 3, resulting from the SIL experiment. This result corresponds to the case study in Section 4.5.
Figure 41. Trajectory tracking in the 3D view of ProVANT UAV 3, resulting from the SIL experiment. This result corresponds to the case study in Section 4.5.
Aerospace 12 00762 g041
Figure 42. Translational positions (x, y, z), attitude angles roll ( ϕ ), pitch ( θ ), and yaw ( ψ ) expressed in Euler angles using the ZYX convention about the local axes, along with the tilting angles ( α R , α L ) of the right and left servomotors, obtained from the SIL experiment. This result corresponds to the case study in Section 4.5.
Figure 42. Translational positions (x, y, z), attitude angles roll ( ϕ ), pitch ( θ ), and yaw ( ψ ) expressed in Euler angles using the ZYX convention about the local axes, along with the tilting angles ( α R , α L ) of the right and left servomotors, obtained from the SIL experiment. This result corresponds to the case study in Section 4.5.
Aerospace 12 00762 g042
Figure 43. Forces generated by the propellers ( F R , F L ), torques applied to the thruster assemblies by the servomotors ( τ R , τ L ), deflections of the elevator and rudder aerodynamic control surfaces ( δ e , δ r ). This result corresponds to the case study in Section 4.5.
Figure 43. Forces generated by the propellers ( F R , F L ), torques applied to the thruster assemblies by the servomotors ( τ R , τ L ), deflections of the elevator and rudder aerodynamic control surfaces ( δ e , δ r ). This result corresponds to the case study in Section 4.5.
Aerospace 12 00762 g043
Figure 44. The ProVANT EMERGENTIA mechanical design.
Figure 44. The ProVANT EMERGENTIA mechanical design.
Aerospace 12 00762 g044
Figure 45. Block diagram illustrating the control strategy implemented via SIL for the ProVANT EMERGENTIA UAV, designed to operate across this UAV’s entire flight envelope [28].
Figure 45. Block diagram illustrating the control strategy implemented via SIL for the ProVANT EMERGENTIA UAV, designed to operate across this UAV’s entire flight envelope [28].
Aerospace 12 00762 g045
Figure 46. ProVANT EMERGENTIA trajectory tracking in the 3D view, resulting from the SIL experiment. This result corresponds to the case study in Section 4.6.
Figure 46. ProVANT EMERGENTIA trajectory tracking in the 3D view, resulting from the SIL experiment. This result corresponds to the case study in Section 4.6.
Aerospace 12 00762 g046
Figure 47. Translational positions (x, y, z), attitude angles roll ( ϕ ), pitch ( θ ), and yaw ( ψ ) expressed in Euler angles using the ZYX convention about the local axes, along with the tilting angles ( α R , α L ) of the right and left servomotors, obtained from the SIL experiment. This result corresponds to the case study in Section 4.6.
Figure 47. Translational positions (x, y, z), attitude angles roll ( ϕ ), pitch ( θ ), and yaw ( ψ ) expressed in Euler angles using the ZYX convention about the local axes, along with the tilting angles ( α R , α L ) of the right and left servomotors, obtained from the SIL experiment. This result corresponds to the case study in Section 4.6.
Aerospace 12 00762 g047
Figure 48. Angular velocities of the propellers ( n P R , n P L ), torques applied to the thruster assemblies by the servomotors ( τ R , τ L ), deflections of the aerodynamic control surfaces ( δ e , δ r ), and external disturbances (environment wind, wind gusts, and applied forces), obtained from the SIL experiment. For clarity, the tail control surfaces are represented by the equivalent elevator and rudder deflections, computed as δ e = 1 2 ( δ T R + δ T L ) and δ r = 1 2 ( δ T R δ T L ) , where δ T R and δ T L denote the deflections of the right and left tail control surfaces, respectively. This result corresponds to the case study in Section 4.6.
Figure 48. Angular velocities of the propellers ( n P R , n P L ), torques applied to the thruster assemblies by the servomotors ( τ R , τ L ), deflections of the aerodynamic control surfaces ( δ e , δ r ), and external disturbances (environment wind, wind gusts, and applied forces), obtained from the SIL experiment. For clarity, the tail control surfaces are represented by the equivalent elevator and rudder deflections, computed as δ e = 1 2 ( δ T R + δ T L ) and δ r = 1 2 ( δ T R δ T L ) , where δ T R and δ T L denote the deflections of the right and left tail control surfaces, respectively. This result corresponds to the case study in Section 4.6.
Aerospace 12 00762 g048
Figure 49. The VERSATILE UAV details.
Figure 49. The VERSATILE UAV details.
Aerospace 12 00762 g049
Figure 50. Translational positions (x, y, z), attitude angles roll ( ϕ ), pitch ( θ ), and yaw ( ψ ) expressed in Euler angles using the ZYX convention about the local axes obtained from the SIL experiment. This result corresponds to the case study in Section 4.7.
Figure 50. Translational positions (x, y, z), attitude angles roll ( ϕ ), pitch ( θ ), and yaw ( ψ ) expressed in Euler angles using the ZYX convention about the local axes obtained from the SIL experiment. This result corresponds to the case study in Section 4.7.
Aerospace 12 00762 g050
Figure 51. Tilting angles ( α R f , α L f , α R b , α L b ) of the right and left servomotors from the frontal and rear parts of the UAV, and torques applied to the thruster assemblies by the servomotors ( τ R f , τ L f , τ R b , τ L b ), obtained from the HIL experiment. This result corresponds to the case study in Section 4.7.
Figure 51. Tilting angles ( α R f , α L f , α R b , α L b ) of the right and left servomotors from the frontal and rear parts of the UAV, and torques applied to the thruster assemblies by the servomotors ( τ R f , τ L f , τ R b , τ L b ), obtained from the HIL experiment. This result corresponds to the case study in Section 4.7.
Aerospace 12 00762 g051
Figure 52. Forces applied by the frontal and rear propellers ( f R f , f L f , f R b , f L b ), and deflections of the aerodynamic control surfaces ( δ C , δ W , δ V ) obtained from the HIL experiment. This result corresponds to the case study in Section 4.7.
Figure 52. Forces applied by the frontal and rear propellers ( f R f , f L f , f R b , f L b ), and deflections of the aerodynamic control surfaces ( δ C , δ W , δ V ) obtained from the HIL experiment. This result corresponds to the case study in Section 4.7.
Aerospace 12 00762 g052
Figure 53. Control law execution time for the case study in Section 4.7.
Figure 53. Control law execution time for the case study in Section 4.7.
Aerospace 12 00762 g053
Table 1. Feature comparison between the ProVANT Simulator and the presented related works.
Table 1. Feature comparison between the ProVANT Simulator and the presented related works.
FeatureAuRoRARotorSROS ControlGazeboFlightGearX-PlaneArduPilot SITLPX4 SITLUnreal EngineMatlabProVANT Simulator
Open Source CodeYYYYNNYYNNY
SIL SupportYYNYYYYYYYY
HIL SupportYNNNNNNNNYY
Tridimensional Visual
Simulation Feedback
NNNYYYNNYNY
Support for Slow
Running Controllers
NNNNNNNNNYY
ROS IntegrationNYYYNNNYNYY
Configurable Physics
Engine
NNNYNNNNYNY
MATLAB IntegrationNNNNNNNNNYY
Graphical User
Interface
NNNYYYNNYYY
Table 2. Parameters of the Quadrotor UAV.
Table 2. Parameters of the Quadrotor UAV.
ParameterValue
Mass of the quadrotor (m)2.24 kg
Distance between the rotors and the vehicle’s
center of gravity (l)0.332 m
Maximum UAV height (h)0.18 m
Drag coefficient of the rotors ( k τ ) 1.7   ×   10 7 N·m · s 2
Thrust coefficient of the rotors ( b ) 9.5   ×   10 6 s 2
Torque/force conversion coefficient ( c τ f )0.018 m
Moment of inertia around the x-axis ( I x x )0.0363 kg· m 2
Moment of inertia around the y-axis ( I y y )0.0363 kg· m 2
Moment of inertia around the z-axis ( I z z )0.0615 kg· m 2
Minimum thrust force of each propeller0 N
Maximum thrust force of each propeller12.3 N
Table 3. Parameters of the unmanned aerial manipulator.
Table 3. Parameters of the unmanned aerial manipulator.
ParameterValue
Distance between the rotors and the quadrotor
center of gravity ( l ) 0.3 (m)
Distance between the quadrotor center of gravity and
the base of the manipulator ( l 0 ) 0.1165 (m)
Thrust coefficient of the rotors ( b ) 9 . 510 6 (N·s2/rad2)
Drag coefficient of the rotors ( k τ ) 1 . 710 7 (N·m·s2/rad2)
Propeller’s radius ( r ) 0.127 (m)
Small tilt angle of the propellers toward the geometric
center of the quadrotor UAV ( α T ) 5 (°)
Friction coefficient of the joints ( μ β 1 , μ β 2 , μ β 3 ) 0.30485 ( N · s / m )
Mass of the quadrotor ( m C 0 ) 2.24 (kg)
Mass of the manipulator links ( m C 1 , m C 2 , m C 3 ) 0.2 (kg)
Inertia tensors matrix of the quadrotor ( I C 0 ) diag 1.18 , 2.35 , 1.17 · 10 2 (kg·m2)
Inertia tensors of the manipulator links ( I C 1 , I C 2 , I C 3 ) diag 1.1 , 1.1 , 1.2 · 10 3 (kg·m2)
Denavit-Hartenberg parameters for the manipulator
link d i (m) θ i (rad) a i (m) α i (rad)
l 1 0 β 1 + 0.3670 0.0765 0
l 2 0 β 2 + 2.5813 0.1485 0
l 3 0 β 3 + 2.9486 0.1635 0
l 4 0000
Table 4. Parameters of the ProVANT UAV 2 with suspended load.
Table 4. Parameters of the ProVANT UAV 2 with suspended load.
ParameterValue
Mass of the load ( m L ) 0.5 (kg)
Mass of the main body of the ProVANT UAV 2 ( m 1 ) 1.707 (kg)
Mass of the thruster assembly ( m 2 , m 3 ) ( 0.0898 , 0.0898 ) (kg)
Distance from the rigid cable attachment point to
the load’s center of gravity ( d A 1 L ) [ 0 0 0.5 ] (m)
Distance from the body reference frame to
the rigid cable attachment point ( d B A 1 ) [ 0 0 0.119 ] (m)
Distance from the body reference frame to
the main body’s center of gravity ( d C 1 B ) [ 0.00432 0.0006 0.0451 ] (m)
Distance from the body reference frame to
the servomotor rotation axis ( d A 2 B ) [ 0 0.2754 0.0562 ] (m)
Distance from the body reference frame to
the servomotor rotation axis ( d A 3 B ) [ 0 0.2754 0.0562 ] (m)
Distance from the servomotor rotation axis to
the thruster assembly center of gravity ( d C 2 A 2 ) [ 0 0 0.056472 ] (m)
Distance from the servomotor rotation axis to
the thruster assembly center of gravity ( d C 3 A 3 ) [ 0 0 0.0565 ] (m)
Load inertia tensor ( I L ) 8.333 · 10 6 · I 3 × 3 (kg · m 2 )
Main body inertia tensor ( I 1 ) 404 0.86 9.65 0.86 881 0.87 9.65 0.87 4173 · 10 6 ( kg · m 2 )
Thruster assembly inertia tensor ( I 2 , I 3 ) 335 0 0 0 335 0 0 0 641 · 10 6 ( kg · m 2 )
Drag coefficient of the rotor ( k τ ) 1.7·10−7 (N·m·s2)
Thrust coefficient of the rotor ( b ) 9.5·10−6 (N·s2)
Small propeller tilt angle toward the geometric
center of the ProVANT UAV 2 ( β ) ( 5 )
Rigid cable viscous friction ( μ γ ) 0.005 (N·m/(rad/s))
Servomotor viscous friction ( μ α ) 0.005 (N·m/(rad/s))
Table 5. Paths that compose the trajectory to be tracked by the load.
Table 5. Paths that compose the trajectory to be tracked by the load.
Time (s) x tr ( t ) (m) y tr ( t ) (m) z tr ( t ) (m)
0 t < 10 0.01 t 2 cos π t 4 sin π t 20 sin π t 4 3.5 2.5 cos π t 10
10 t < 19 π 4 ( t 10 ) 16
19 t < 20 9 π 4 0.5 sin π 2 ( t 19 ) 1.5 0.5 cos π 2 ( t 19 ) 6
20 t < 29 9 π 4 0.5 1.5 + π 4 ( t 20 ) 6
29 t < 30 9 π 4 0.5 cos π 2 ( t 29 ) 1.5 + 9 π 4 + 0.5 sin π 2 ( t 29 ) 6
30 t < 40 9 π 4 + π 4 ( t 30 ) 2 + 9 π 4 6
40 t π 80 t 2 + 5 π 4 t 119 π 4 2 + 9 π 4 3.5 + 2.5 cos π 10 ( t 40 )
Table 6. Parameters of the simulated sensors.
Table 6. Parameters of the simulated sensors.
SensorNoise LimitsSampling TimePDF
GPS ± 0.15 m 120 msGaussian (truncated)
Barometer ± 0.51 m 12  msGaussian (truncated)
IMU ± 2.618 · 10 3 rad, ±   16.558 · 10 3 rad/s12  msGaussian (truncated)
Camera ± 0.005 m, ± 0.02  m 24 msUniform
Servos ± 5.67 · 10 3 rad, ±   0.50772 rad/s12  msUniform
Table 7. Parameters of the ProVANT UAV 3.
Table 7. Parameters of the ProVANT UAV 3.
ParameterValue
Mass of the main body of
the ProVANT UAV 3 ( m c 1 ) 1.554 (kg)
Mass of the thruster assembly ( m c 2 , m c 3 ) ( 0.084 , 0.084 ) (kg)
Distance from the body reference frame to
the main body’s center of gravity ( d c 1 B ) 0.008 0 0.043 (m)
Distance from the body reference frame to
the servomotor rotation axis ( d c 2 a u x B ) 0.00059 0.27 0.066 (m)
Distance from the body reference frame to
the truster assembly center of gravity ( d c 2 c 2 a u x ) 0 0 0.05401 (m)
Distance from the body reference frame to
the servomotor rotation axis ( d c 3 a u x B ) 0.00059 0.27 0.066 (m)
Distance from the servomotor rotation axis to
the truster assembly center of gravity ( d c 3 c 3 a u x ) 0 0 0.05401 (m)
Main body inertia tensor ( I c 1 ) 47.88 0 3.63 0 22.75 0 3.63 0 60.62 · 10 3 (kg·m2)
Thruster assembly inertia tensor ( I c 2 , I c 3 ) diag ( 4.04 , 3.8 , 1.58 ) · 10 5 (kg·m2)
Small propeller tilt angle toward
the geometric center of the ProVANT UAV 3 ( μ ) 4 (deg)
Drag coefficient of the rotor ( k τ ) 1.7 × 10 7
Thrust coefficient of the rotor (b) 9.5 × 10 6
Table 8. Parameters of the ProVANT EMERGENTIA UAV.
Table 8. Parameters of the ProVANT EMERGENTIA UAV.
ParameterValue
Mass of the main body of
the ProVANT EMERGENTIA UAV ( m 1 ) 7 (kg)
Mass of the thruster assembly ( m 2 , m 3 ) ( 0.3 , 0.3 ) (kg)
Distance from the body reference frame to
the main body’s center of gravity ( d C 1 B ) [ 0.05 , 0 , 0.12 ] (m)
Distance from the body reference frame to
the servomotor rotation axis ( d A 2 B ) [ 0.03 , 1.025 , 0.292 ] (m)
Distance from the body reference frame to
the servomotor rotation axis ( d A 3 B ) [ 0.03 , 1.025 , 0.292 ] (m)
Distance from the servomotor rotation axis to
the thruster assembly center of gravity ( d C 2 A 2 ) [ 0 , 0 , 0.07 ] (m)
Distance from the servomotor rotation axis to
the thruster assembly center of gravity ( d C 3 A 3 ) [ 0 , 0 , 0.07 ] (m)
Main body inertia tensor ( I 1 ) 2.72 0 0 0 7.44 0 0 0 9.95 · ( kg · m 2 )
Thruster assembly inertia tensor ( I 2 , I 3 ) diag ( 0.005 , 0.005 , 0.002 ) ( kg · m 2 )
Servomotor viscous friction ( μ α ) 0.005 (N· m/(rad/s))
Table 9. Parameters of the ProVANT VERSATILE UAV.
Table 9. Parameters of the ProVANT VERSATILE UAV.
ParameterValue
Mass of the main body of
the ProVANT EMERGENTIA UAV ( m 1 ) 19.067 (kg)
Mass of the front thruster assembly ( m 2 , m 3 ) ( 0.519 , 0.519 ) (kg)
Mass of the rear thruster assembly ( m 4 , m 5 ) ( 1.076 , 1.076 ) (kg)
Distance from the body reference frame to
the main body’s center of gravity ( d C 1 B ) [ 0.13 0 0.15 ] (m)
Distance from the body reference frame to the right
front servomotor rotation axis ( d A 2 B ) [ 0.274 0.375 0.101 ] (m)
Distance from the body reference frame to the right
rear servomotor rotation axis ( d A 5 B ) [ 0.31 0.57 0.01 ] (m)
Distance from the front servomotor rotation axis to
the front thruster assembly center of gravity ( d C 2 A 2 ) [ 0 0 0.0045 ] (m)
Distance from the rear servomotor rotation axis to
the rear thruster assembly center of gravity ( d C 5 A 5 ) [ 0.0177 0 0.083 ] (m)
Main body inertia tensor ( I 1 ) 0.444 0 0.143 0 1.255 0 0.143 0 1.614 · ( kg · m 2 )
Thruster assembly inertia tensor ( I 2 , I 3 ) diag ( 2.26 , 2.26 , 0.41 ) × 10 3 ( kg · m 2 )
Thruster assembly inertia tensor ( I 4 , I 5 ) 9 , 36 0 1 , 2 0 12 0 1.2 0 3.206 × 10 3 ( kg · m 2 )
Servomotor viscous friction ( μ α ) 0.005 (N·m/(rad/s))
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Morais, J.E.; Cardoso, D.N.; Rego, B.S.; Andrade, R.; Nascimento, I.B.P.; Pereira, J.C.; Campos, J.M.; Santiago, D.F.; Santos, M.A.; Becker, L.B.; et al. ProVANT Simulator: A Virtual Unmanned Aerial Vehicle Platform for Control System Development. Aerospace 2025, 12, 762. https://doi.org/10.3390/aerospace12090762

AMA Style

Morais JE, Cardoso DN, Rego BS, Andrade R, Nascimento IBP, Pereira JC, Campos JM, Santiago DF, Santos MA, Becker LB, et al. ProVANT Simulator: A Virtual Unmanned Aerial Vehicle Platform for Control System Development. Aerospace. 2025; 12(9):762. https://doi.org/10.3390/aerospace12090762

Chicago/Turabian Style

Morais, Junio E., Daniel N. Cardoso, Brenner S. Rego, Richard Andrade, Iuro B. P. Nascimento, Jean C. Pereira, Jonatan M. Campos, Davi F. Santiago, Marcelo A. Santos, Leandro B. Becker, and et al. 2025. "ProVANT Simulator: A Virtual Unmanned Aerial Vehicle Platform for Control System Development" Aerospace 12, no. 9: 762. https://doi.org/10.3390/aerospace12090762

APA Style

Morais, J. E., Cardoso, D. N., Rego, B. S., Andrade, R., Nascimento, I. B. P., Pereira, J. C., Campos, J. M., Santiago, D. F., Santos, M. A., Becker, L. B., Esteban, S., & Raffo, G. V. (2025). ProVANT Simulator: A Virtual Unmanned Aerial Vehicle Platform for Control System Development. Aerospace, 12(9), 762. https://doi.org/10.3390/aerospace12090762

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop