Main Content

PX4 Hardware-in-the-Loop (HITL) Simulation with VTOL 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 Pixhawk 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.

This example demonstrates these procedures.

  • Manual control with Simulink dashboard controls.

  • Execute a mission hard-coded in Simulink.

Prerequisites

You must complete these before proceeding with this example:

  1. If you are new to Simulink, watch the Simulink Quick Start video.

  2. Set up the physical connection for HITL simulation between the Pixhawk autopilot and host computer running Simulink as shown in PX4 Hardware-in-the-Loop System Architecture.

  3. Configure and set up the Pixhawk 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.

  4. 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 Pixhawk Series board as the PX4 Autopilot board to any Pihxawk series board. This example uses Cube Orange +.

QGroundControl airframe selection, with HIL Standard VTOL QuadPlane highlighted.

Specify these parameters for the airframe in QGroundControl to avoid triggering auto-landing when the VTOL is hovering:

  • LNDMC_XY_VEL_MAX 0 m/s

  • LNDMC_Z_VEL_MAX 0 m/s

  • LNDMC_ROT_MAX 0 rad/s

This diagram illustrates the HITL configuration and the physical communication between various modules.

Required Third-Party Software

Required Hardware

  • Pixhawk series flight controller

  • Micro-USB (Universal Serial Bus) type-B cable

  • Micro-SD card

Getting Started

Load the project, set up the aircraft plant model and parameters for the HITL simulation.

prj = openProject("PX4VTOLHITLSimulinkPlant/VTOLHITL.prj");

Alternatively, you can set up the model by using the setupHITLConfiguration, setupPlantControllerParams, and setupHITLController helper functions and assigning the controller and plant models.

% Set HITL configuration parameters
setupHITLConfiguration

% Initialize plant parameters
setupPlantControllerParams

% Initialize controller parameters
setupHITLController

% Controller and plant model 
controller_mdl = "HITL_Controller_top.slx";
plant_mdl = "HITL_Plant_top.slx";

Set Up Mission with Transition

This section loads the guidance mission which, has flight modes like take-off (in hover), forward transition, fixed-wing. and backward transition.

You can load a sample mission by using the setupHITLTransitionGuidanceMission helper function. In this sample mission, the helper function loads exampleHelperTransitionMissionData.m which is a mission in which the UAV takes off, transitions to fixed wing, and performs guided flight.

setupHITLTransitionGuidanceMission

You can customize your flight mission using these modes, based on the format that the Path Manager uses.

  • MIssion Mode 1 - Takeoff UAV

  • MIssion Mode 2 - Fly to a waypoint

  • MIssion Mode 3 - Orbit a point

  • MIssion Mode 4 - Land UAV

  • MIssion Mode 6 - Transition from hover to forward flight or transition to hover from forward flight.

Modes 1 and 4 support only hover mode. Modes 2, 3, and 6 support fixed-wing mode and hover mode.

Alternatively, you can load a predefined hover guidance mission.

setupHITLHoverGuidanceMission;

Deploy to Pixhawk Target

In the HITL controller model, the VTOL Controller subsystem contains a reference flight controller design for a VTOL tilt-rotor UAV model. The Actuator output subsystem parses the controller outputs into uORB messages. The Estimator output subsystem provides the estimated states of the UAV for controller feedback.

Open the HITL_controller_top model.

open_system(controller_mdl)

To deploy the model, on the Hardware tab of the Simulink Toolstrip, in the Deploy section, select Build, Deploy & Start. Simulink generates the code for the flight controller and deploys it to the Pixhawk board.

After completing deployment, the model launches QGroundControl.

  1. 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

  2. If you have changed the hardware, or are not using the preconfigured Simulink model, then you must configure your Simulink model as in Configure Simulink Model for Deployment in Hardware-in-the-Loop (HITL) Simulation.

Run VTOL Plant Model

To simulate the mission in HITL, open the HITL_Plant_top model. In this model, the MAVLink Bridge Source block reads the MAVLink messages from the Pixhawk board and feeds them to the VTOL Plant subsystem as actuator inputs.

The VTOL Plant subsystem contains the plant model for the VTOL tilt-rotor UAV, which simulates the aerodynamics, propulsion, ground contact, and sensors of a VTOL tilt-rotor UAV. The subsystem outputs sensor, GPS, rotor parameter, and GPS data. The MAVLink Brisge Sink block then receives this data, parses it as MAVLink messages, and sends the messages back to the Pixhawk using the serial connection.

open_system(plant_mdl)

On the Simulink Toolstrip, in the Simulation tab, select Run to start the simulation

Open QGroundControl and select Fly View. Start the mission by arming the vehicle by selecting Arm.

QGroundControl user interface which shows the location of the Arm button on the sensor status pane

In this mission, the UAV takes off and transitions into fixed-wing mode.

Discard changes to reset the example.

discardChanges(myDictionaryObj)