PX4 Hardware-in-the-Loop (HITL) Simulation with VTOL UAV Tilt-Rotor Plant in Simulink
This example shows how to use the UAV Toolbox Support Package for PX4® Autopilots to verify a UAV controller design by using Hardware-in-the-Loop (HITL) simulation on a PX4 Autopilot autopilot and simulating the VTOL tilt rotor UAV Dynamics in Simulink®.
You can use the Simulink model in this example as a reference to design a flight controller algorithm for take-off, hover, waypoint following, forward transition, back transition, and landing for a VTOL tilt-rotor UAV plant model. The plant model in this example simulates the aerodynamics, propulsion, ground contact, and sensors of a VTOL tilt-rotor UAV.
Prerequisites
You must complete these before proceeding with this example:
If you are new to Simulink, watch the Simulink Quick Start video.
Set up the physical connection for HITL simulation between the PX4 Autopilot and host computer running Simulink as shown in PX4 Hardware-in-the-Loop System Architecture.
Configure and set up the PX4 Autopilot in HITL mode as shown in Setting up PX4 Autopilot in Hardware-in-the-Loop (HITL) Mode from QGroundControl. When seelcting an airframe, choose the
HIL Standard VTOL QuadPlane
.Set up the PX4 firmware as described in Set Up PX4 Firmware for Hardware-in-the-Loop Simulation. At the Select a PX4 Autopilot and Build Target step, set any PX4 Autopilot as the PX4 Autopilot board. Select the VTOL specific px4board build target from the dropdown list. For example if you are using Cube Orange + as the Autopilot, choose cubepilot_cubeorangeplus_VTOL as the px4board build target. This example uses
Cube Orange +
.
Specify these parameters for the airframe in QGroundControl to avoid triggering auto-landing when the VTOL is hovering:
LNDMC_XY_VEL_MAX —
0
m/sLNDMC_Z_VEL_MAX —
0
m/sLNDMC_ROT_MAX —
0
rad/s
This diagram illustrates the HITL configuration and the physical communication between various modules.
Required Third-Party Software
Required Hardware
PX4 Autopilot flight controller
Micro-USB (Universal Serial Bus) type-B cable
Micro-SD card
Getting Started
To open the example livescript and directory which contains the Simulink project file, first run openExample('uav/PX4HITLSimulationWithVTOLTiltRotorSimulinkExample')
in the command window.
You must open the VTOLRefApp.prj
project file to access the Simulink model, supporting files, and project shorcuts that this example uses.
% Open the Simulink project after running openExample('uav/PX4HITLSimulationWithVTOLTiltRotorSimulinkExample') prj = openProject("VTOLApp");
Use the highlighted project shortcuts to set up the HITL plant and controller models, open the HITL plant and controller models, and select the type of mission that you want to simulate.
To initialize the parameters and configurations of the HITL plant model, click the Initialize Plant Parameters shortcut or run the setupHITLConfiguration
helper function.
setupHITLConfiguration
To initialize the parameters and configurations of the HITL controller model, click the Initialize Controller Parameters shortcut or run the setupHITLController
helper function.
setupHITLController
Set Up Mission with Transition
This example contain a sample mission in which the UAV takes off, transitions to fixed wing, and performs guided flight that is defined in the exampleHelperTransitionMissionData.m
file.
Load the sample mission by clicking the HITL Full Transition Mission shortcut or by using the setupHITLTransitionGuidanceMission
helper function.
setupHITLTransitionGuidanceMission
Alternatively, you can load a predefined hover guidance mission by clicking the HITL Hover Mission shortcut or by using the setupHITLHoverGuidanceMission
helper function.
To create your own mission, you can customize the mission defined in the exampleHelperTransitionMissionData.m
file. The following table summarize different mission modes and the corresponding flight modes. Note that the modes are based on the format that the Path Manager uses.
Mission Mode | Action | Supported Flight Mode |
---|---|---|
1 | Takeoff | Hover |
2 | Waypoint | Hover, Fixed Wing |
3 | Orbit | Hover, Fixed Wing |
4 | Land | Hover |
5 (Not used in this example) | RTL (Not used in this example) | N/A (Not used in this example) |
6 | Transition | Hover, Fixed Wing |
Deploy HITL Controller Model to PX4 Autopilot Target
The HITL_controller_top.slx
file contains the HITL controller model. The model consists of the following subsystems:
VTOLAutopilotController
— Reference flight controller design for a VTOL tilt-rotor UAV model.Actuator outputs
— Parses theVTOLAutopilotController
subsystem outputs into uORB messages.Estimator
— Obtains VTOL UAV states from PX4 estimator for controller feedback.
Open the HITL_controller_top.slx
model using the Open HITL Controller Model shortcut, or use the following code block.
controller_mdl = "HITL_Controller_top.slx";
open_system(controller_mdl)
Warning: Unrecognized function or variable 'CloneDetectionUI.internal.CloneDetectionPerspective.register'.
To generate the code of the flight controller model and deploy it to the PX4 Autopilot board, select Build, Deploy & Start on the Hardware tab of the Simulink Toolstrip.
After completing deployment, the model launches QGroundControl.
Note :
If you are using Ubuntu, QGroundCcontrol might not launch automatically. To launch QGroundCcontrol, open the terminal and go to the folder where QGroundCcontrol is downloaded and , and then enter this command:
./QGroundControl.AppImage
If you have changed the hardware, or are not using the pre-configured Simulink model, then you must configure your Simulink model as explained in Configure Simulink Model for Deployment in Hardware-in-the-Loop (HITL) Simulation. Run the following code block to launch the Configuration Parameters dialog in a new window.
configObj = getActiveConfigSet('VTOLAutopilotController');
deploymentConfigSet = getRefConfigSet(configObj);
openDialog(deploymentConfigSet);
Run HITL Simulation
The HITL_Plant_top.slx
file contains the HITL plant model. The model consists of the following blocks:
MAVLink Bridge Source
block — Reads the MAVLink messages from the PX4 Autopilot board and sends it toVTOL Plant
subsystemVTOL Plant
subsystem — Plant model for the VTOL tilt rotor UAV, which simulates the aerodynamics, propulsion, ground contact, and sensors. The subsystem outputs sensor, rotor parameter, and GPS data.MAVLink Bridge Sink
block — ParsesVTOL Plant
subsystem as MAVLink messages and sends the messages back to PX4 Autopilot by using serial connection
Open the HITL_Plant_top.slx
model by using the Open HITL Plant Model shortcut or by running the following code block.
plant_mdl = "HITL_Plant_top.slx";
open_system(plant_mdl)
Warning: Unrecognized function or variable 'CloneDetectionUI.internal.CloneDetectionPerspective.register'.
Configure the Serial Port parameter of the MAVLink Bridge Source
and the MAVLink Bridge Sinks
blocks to match the COM port that you use to connect the PX4 autopilot.
To start the HITL simulation, run the HITL_Plant_top.slx
model
Then, Open QGroundControl and configure the actuators as shown. For more information, see Configure and Assign Actuators in QGC.
Next, select Fly View in QGroundControl. Arm the VTOL UAV to start the mission by selecting Arm.
After the VTOL UAV is armed, the UAV takes off and transitions into fixed-wing mode to complete the mission.
Discard changes to reset the example.
discardChanges(myDictionaryObj); close_system(controller_mdl,0);