Main Content

PX4 in Hardware-in-the-Loop (HITL) Simulation with jMAVSim Simulator

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 against the jMAVSim simulator.

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

This example shows how to create a guidance and control algorithm, which takes in waypoints from the QGC, reads 'vehicle_local_position', 'vehicle_attitude' uORB topics from the estimator, and outputs the actuator values through the PWM block. The control and guidance structure in this example builds on top of the examples listed below. It is recommended to go through these examples to get a better understanding of the control architecture.

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 (already used during the initial Hardware Setup>)

  • Serial-to-USB FTDI converter

Model

To get started, launch the px4demo_QGCWaypointFollower_hitl example.

Once the model opens, it will load the required workspace variables.

Model Architecture and Conventions

This example model consists of the following subsystems:

  • Guidance subsystem: Takes in the previous, current, next waypoints and the waypoint type from the Read Position block, and designs the logic for Take-off, Land, and Waypoint follower mode. The Waypoint subsystem uses the UAV Toolbox Waypoint Follower block to determine the position setpoints for the Control and Actuator subsystem.

Task 1 - Make the Hardware Connections

In this task, you will connect your Pixhawk board to the host computer using the USB cable. Decide the serial port on the Pixhawk series board for connecting the host computer. For example, consider Pixhawk 6x as the hardware board, then connect the GPS2(/dev/ttyS7) serial port and the USB port on host computer by using an Serial-to-USB FTDI converter as shown in the sample image below. For more information, see Running Monitor & Tune Simulation over FTDI with Pixhawk 6x.

Task 2 - Configure the Model

In this task, you will configure a Simulink model and enable calibration of parameters in third-party calibration tools.

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.

1. Open the model.

2. Go to Modeling > Model Settings to open the Configuration Parameters dialog box.

3. Open the Hardware Implementation pane, and select any Pixhawk Series board.

4. Expand Target hardware resources for that board.

5. Click HITL and then select Enable HITL Mode. Enabling HITL mode ensures that jMAVSim simulator and QGC are automatically configured and launched to run along with the Simulink model.

Note: If you are using Ubuntu, then jMAVSim simulator and QGC might not launch automatically. Perform these steps to launch jMAVSim simulator and QGC.

To launch jMAVSim simulator, open Terminal and go to the location where firmware is downloaded and run the following command:

./Tools/jmavsim_run.sh -q -s -d COM9 -b 921600 -r 250

In the above command, replace the host serial port name COM9 as appropriate. You must enter the Host serial port name of the main USB connection with the Pixhawk and not the FTDI host serial port name.

To launch QGC, open Terminal and go to the location where QGC is downloaded and run the following command:

./QGroundControl.AppImage

6. Click External mode and select /dev/ttyS7 as the Hardware board serial port.

Note: If you select PX4 Pixhawk 6x hardware board, then configure /dev/ttyS7 tab. If you select any other Pixhawk Series board, configure the appropriate /dev/tty tab.

7. Clear the Use the same host serial port for External mode as used for firmware upload option.

8. In the Host Serial port parameter, enter the host serial port number on the host computer for External mode communication.

9. Click MAVLink and ensure that Enable MAVLink on /dev/ttyACM0 option is selected.

10. Click /dev/ttyS7 and set the Baud rate to 115200. Do not change any other parameters.

11. Click Apply and then click OK.

Task 3 - Initiate Monitor and Tune Action for the Model

1. On the Hardware tab, in the Mode section, select Run on board and then click Monitor & Tune.

This launches QGC and jMAVSim.

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

3. Create a mission or upload the preplanned mission, Mission.plan available with this example.

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

  • Upload a mission: Click Open Example at the top of this page to save the plan file to your computer. After you save the .plan file, launch QGC, and click File > Open to upload the plan to the QGC.

After you upload the plan, the mission is visible in QGC.

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

Note: If the hardware board is restarted after the mission is uploaded, then the mission may not work if the QGC and jMAVSim are open. Restart QGC, jMAVSim, and upload the mission again to solve the issue.

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

6. Start the Mission in QGC.

After the mission is started, the drone takes off and follows the set of waypoints from QGC. A sample screen is shown here.

Other Things to Try

Try the Survey mission from QGC and re-calibrate the controller, if required for optimal performance. For information on setting up the survey mission, see Creating a Survey.