Main Content

Scenario Simulation and Flight Visualization with PX4 Hardware-in-the-Loop (HITL) and UAV Dynamics in Simulink

This example demonstrates 3D scenario Simulation and Flight visualization with PX4® Hardware-in-the-Loop (HITL) and UAV Dynamics contained in Simulink®. Unreal Engine® simulation environment is used for the 3D scenario Simulation and visualization. For more information, see Unreal Engine Simulation for Unmanned Aerial Vehicles.

Limitation: The Unreal Engine simulation environment is supported only on Microsoft® Windows® system.

Prerequisites

Required Third-Party Software

This example requires this third-party software:

Required Hardware

To run this example, you will need the following hardware:

  • Pixhawk Series flight controller

  • Micro USB type-B cable

  • Micro-SD card

  • Pixhawk serial port connectors.

Workflow to Run Unreal Engine Flight Visualization Model Along with Pixhawk in HITL Mode

This example uses three different Simulink models.

  • Simulink model for Flight Controller to be deployed on PX4 Autopilot.

  • Simulink model for UAV Dynamics and sensor simulation.

  • Simulink model for flight visualization with Unreal Engine Simulation for Unmanned Aerial Vehicles.

To avoid performance degradation in MATLAB® due to three different Simulink models running at the same time, launch two separate sessions of same MATLAB.

In first session of MATLAB, the Flight Controller will be deployed on the Autopilot and the UAV Dynamics model will be running on host computer communicating with Autopilot.

In second session of MATLAB, the Simulink model for flight visualization with Unreal Engine Simulation will be running.

Step 1: Make Hardware Connections and Setup the Pixhawk in HITL Mode

The below diagram illustrates the HITL setup and the physical communication between various modules.

1. Connect your Pixhawk board to the host computer using the USB cable.

2. Ensure that you have configured the Pixhawk board in HITL mode as documented in Setting Up PX4 Autopilot in Hardware-in-the-Loop (HITL) Mode from QGroundControl.

3. Ensure that you have setup the PX4 Firmware as mentioned in Set Up PX4 Firmware for Hardware-in-the-loop (HITL) Simulation.

Step 2: Launch First Session of MATLAB and the MATLAB Project

1. Open MATLAB.

2. Open the px4demo_HardwareInLoopWithSimulinkPlant MATLAB project.

3. Once the Simulink project is open, click the Project Shortcuts tab on the MATLAB window and click Open Autopilot Controller to launch PX4 Controller named Quadcopter_ControllerWithNavigation.

4. In the Project Shortcuts tab, click Open UAV Dynamics to launch the Simulink UAV Dynamics model named UAV_Dynamics_Autopilot_Communication.

5. Open the Simulink Plant model UAV_Dynamics_Autopilot_Communication and a connection for the flight visualization in the MAVLink Bridge Source block. Double-click the MAVLink Bridge Source block to open the block Parameters dialog box.

Step 3: Configure Simulink Controller Model for HITL Mode

1. Follow the instructions mentioned in Configure Simulink Model for Deployment in Hardware-in-the-Loop (HITL) Simulation.

Note: These steps are not required in the pre-configured model. Perform these steps if you have changed the hardware or not using the pre-configured model.

2. Click Build, Deploy & Start from Deploy section of Hardware tab in the Simulink Toolstrip for the Controller model Quadcopter_ControllerWithNavigation.

The code will be generated for the Controller model and the same will be automatically deployed to the Pixhawk board (Pixhawk 6x in this example).

After the deployment is complete, QGroundControl will be automatically launched.

Step 4: Launch Second Session of MATLAB and Open the Flight Visualization Model

1. Launch second session of MATLAB.

2. Open the px4demo_HardwareInLoopWithSimulinkPlant MATLAB project.

3. Once the Simulink project is open, click the Project Shortcuts tab on the MATLAB window and click Open 3D Visualization with Unreal Engine to launch the onboard model named Unreal_3DVisualization.

In this model, The MAVLink data from the PX4 Autopilot is received over UDP (port : 25000) and is used to decode the position and attitude data of the UAV. After coordinate conversion, it is then passed to the Simulation 3D UAV Vehicle block for flight visualization.

4. On the Simulation tab, click Run to simulate the model. Once the model start running, you will see the Unreal simulation environment getting launched. A sample screen is shown below.

Step 5: Run the UAV Dynamics Model, Upload Mission from QGroundControl and Fly the UAV

1. In the Simulink toolstrip of the Plant model (UAV_Dynamics_Autopilot_Communication), on the Simulation tab, click Run to simulate the model.

2. In the QGC, navigate to the Plan View.

3. Create a mission. For information on creating a mission, see Plan View.

After you create a mission, it is visible in QGC.

4. Click Upload button in the QGC interface to upload the mission from QGroundControl.

5. Navigate to Fly View to view the uploaded mission.

6. Start the Mission in QGC. The UAV should follow the mission path and the flight will be simulated in the Unreal environment.

Troubleshooting

  • While Simulating the visualization model in Step 4, you might get any eSTD exceptionc errors such as, "some module could not be found". Change the compiler to Microsoft Visual C++ 2019 using mex --setup C++ command to fix the issue.

  • If the Unreal environment simulation is very slow, ensure that your Host PC is Configured with MATLAB supported GPU (GPU with compute capability of more than 5).