PX4 Autopilot in Hardware-in-the-Loop (HITL) Simulation with UAV Dynamics in Simulink
This example shows how to use the UAV Toolbox Support Package for PX4® Autopilots to verify the controller design by deploying on the Pixhawk® hardware board, in HITL mode with UAV Dynamics contained in Simulink®.
The UAV Toolbox Support Package for PX4 Autopilots enables you to use Simulink to design a flight controller algorithm to follow the mission set in the QGroundControl (QGC). Additionally, you can design the UAV Dynamics in Simulink and simulate sensor values and use the same to communicate with Autopilot in HITL mode instead of third party simulators.
Prerequisites
- If you are new to Simulink, watch the Simulink Quick Start video. 
- Go through the PX4 Hardware-in-the-Loop System Architecture document to understand the physical connections required to setup the Pixhawk and Simulink for HITL Simulation. 
- Configure and set up Pixhawk in HITL mode. For more information, see Setting Up PX4 Autopilot in Hardware-in-the-Loop (HITL) Mode from QGroundControl. 
- Setup the PX4 Firmware as mentioned in Set Up PX4 Firmware for Hardware-in-the-Loop (HITL) Simulation. In the Select a PX4 Autopilot and Build Target screen, select any Pixhawk Series board as the PX4 Autopilot board and corresponding build target having - _multicopterkeyword from the drop-down list. This example uses Pixhawk 6x as autopilot board and- px4_fmu-v6x_multicopterbuild target.
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 (Universal Serial Bus) type-B cable 
- Micro-SD card 
- Serial-to-USB FTDI converter 
- Mini USB cable for FTDI 
- Pixhawk serial port connectors 
Methods to Run HITL Simulation from Simulink
This example has two different Simulink models; one for the Controller to be deployed on Autopilot and another containing the UAV Dynamics and sensor simulation. There are two methods which you can use to execute these two models.
- In the first method, the Controller is deployed on the Autopilot and the UAV Dynamics model will run on MATLAB® on host computer communicating with Autopilot. 
- In the second method, the Controller is deployed on Autopilot and will communicate with MATLAB on host computer using Monitor & Tune Simulation. The UAV Dynamics model will run on MATLAB on host computer communicating with Autopilot. 
For the second method, running two Simulink models in same MATLAB can cause degraded performance of MATLAB. It is recommended to launch two separate sessions of same MATLAB, each one running one Simulink model. In the Method 1, the Controller model is deployed and does not run Monitor & Tune and hence one MATLAB instance is sufficient.
Method 1: Controller Deployed on Autopilot over Normal Mode (No Monitor & Tune)
Step 1: Make Hardware Connections and setup the Pixhawk in HITL mode
The diagram below 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: Open MATLAB Project and Controller and UAV Dynamics model
The support package includes an example project having PX4 controller and the UAV to follow the mission set in the QGroundControl (QGC).
1. Open MATLAB.
2. Open the example MATLAB project by executing this command at the MATLAB command prompt:
openExample('px4/PX4HITLSimulationSimulinkPlantExample')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.

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.
Note: If you are using Ubuntu®, QGC might not launch automatically. To launch QGC, open Terminal and go to the location where QGC is downloaded and run the following command:
./QGroundControl.AppImage
Step 4: Run the UAV Dynamics model, upload Mission from QGroundControl and fly the UAV
1. In the Project Shortcuts tab, click Open UAV Dynamics to launch the Simulink UAV Dynamics model named UAV_Dynamics_Autopilot_Communication.
2. In this model, ensure that the COM ports are set in the MAVLink Bridge Source and MAVLink Bridge Sink blocks. To set the COM port:
- Double-click the block to open the Block Parameters dialog box and then specify the value for the Serial Port (Specify manually) parameter. 
3. In the Simulink toolstrip of the Plant model (UAV_Dynamics_Autopilot_Communication), on the Simulation tab, click Run to simulate the model.

4. Configure the actuators in QGC. For more information, see Configure and Assign Actuators in QGC.

5. Navigate to the Plan View.

6. Create a mission. For information on creating a mission, see Plan View.
After you create a mission, it is visible in QGC.
7. Click Upload button in the QGC interface to upload the mission from QGroundControl.
8. Navigate to Fly View to view the uploaded mission.
9. Start the Mission in QGC. The UAV should follow the mission path.
Method 2: Controller Deployed on Autopilot for Monitor & Tune Simulation
In this method, two separate sessions of the same MATLAB, each one running one Simulink model, are launched. In this method, you can run Monitor and Tune the Model Running on PX4 Autopilots Simulation to tune the algorithm in real time on the autopilot and log the real time signals in Simulink. In this case, an additional serial port is required to establish Monitor & Tune communication with the Autopilot. Since the USB port is already occupied for transferring MAVLink data between host computer and Autopilot in HITL mode, you need to use any of the other available serial ports on the Autopilot. In this example, GPS2 (dev/ttyS7) is used on Pixhawk 6x to communicate with Simulink running on Host Computer using Monitor & Tune Simulation.
Step 1: Make Hardware Connections and setup the Pixhawk in HITL mode
The diagram below illustrates the HITL setup and the physical communication between various modules. Note that the flight controller now communicates to the Pixhawk board GPS2 serial port over FTDI for Monitor & Tune Simulation.

1. Connect your Pixhawk board to the host computer using the USB cable.
2. Connect the Rx & Tx of GPS2 port to the Tx and Rx of the FTDI (Serial to USB Converter) device which is connected to host computer over another USB port. For more information, see Running Monitor & Tune Simulation over FTDI with Pixhawk 6x.
3. Determine the COM Port for the FTDI device on host computer. This can be seen from the Device Manager.
4. 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.
5. Ensure that you have setup the PX4 Firmware as mentioned in Set Up PX4 Firmware for Hardware-in-the-Loop (HITL) Simulation.
Step 2a: Open first instance of MATLAB and launch MATLAB project and Controller model
The support package includes an example project having PX4 controller and the UAV to follow the mission set in the QGroundControl (QGC).
1. Open MATLAB.
2. Open the example MATLAB project by executing this command at the MATLAB command prompt:
openExample('px4/PX4HITLSimulationSimulinkPlantExample')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. Copy the MATLAB Project Path to clipboard.

Step 2b: Open second instance of MATLAB and launch the previous MATLAB Project and UAV Dynamics model
1. Open the second instance of the same MATLAB version.
2. Navigate to the project path previously copied in Step 2a in current MATLAB.

3. Click on the .prj file to launch the same Project in current MATLAB.

4. In the Project Shortcuts tab, click Open UAV Dynamics to launch the Simulink UAV Dynamics model named UAV_Dynamics_Autopilot_Communication.
Step 3: Configure Simulink Controller model for Monitor & Tune Simulation
1. For the Controller model launched in first MATLAB, follow the instructions mentioned in Configure Simulink Model for Monitor & Tune Simulation with Hardware-in-the-Loop (HITL) document.
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 Monitor & Tune from Run on Hardware section of Hardware tab in the Simulink Toolstrip for the Controller model Quadcopter_ControllerWithNavigation

3. The code will be generated for the Controller model and the same will be automatically deployed to the Pixhawk board (in this case Pixhawk 6x). Pixhawk should start communicating with host over Monitor & Tune Simulation.
After the deployment is complete, QGroundControl will be automatically launched. Note: If you are using Ubuntu, QGC might not launch automatically. To launch QGC, open Terminal and go to the location where QGC is downloaded and run the following command:
./QGroundControl.AppImage
Step 4: Run the UAV Dynamics model, upload Mission from QGroundControl and fly the UAV
Follow Step 4 from Method 1, to run the UAV Dynamics model, create and upload mission from QGC and fly the UAV.