Main Content

Uvify IFO-S Autopilot and Nvidia Jetson in Hardware-in-the-Loop (HITL) Simulation with UAV Dynamics Modeled in Simulink

This example shows how to use the UAV Toolbox Support Package for PX4® Autopilots to deploy and verify algorithms on Uvify IFO-S Drone, with NVIDIA® Jetson™ as Onboard computer.

Using this example you,

  • Deploy a flight control algorithm modeled in Simulink® to Uvify IFO-S Autopilot.

  • Deploy an autonomous algorithm to NVIDIA Jetson.

  • Enable Scenario visualization in Unreal Engine®.

  • Perform HITL Simulation of UAV Dynamics and sensors.

Limitation: The Unreal Engine simulation environment is supported only on Microsoft® Windows® system. If you are using a Linux® system, skip adding the 3D scenario simulation step and still be able to complete this example.

Prerequisites

Required Third-Party Software This example requires this third-party software:

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

  • Uvify IFO-S

  • Micro USB type-B cable

  • Micro-SD card

  • NVIDIA Jetson & power adaptor (recommended)

  • Host PC Configured with MATLAB supported GPU. It is recommend to use GPU with compute capability of more than 5.

Workflow to Run Model on NVIDIA Jetson Along with Pixhawk in HITL Mode

The above diagram illustrates the PX4 and NVIDIA Jetson HITL setup and the physical communication between various modules.

This example uses four 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 Autonomous algorithm to be deployed on NVIDIA Jetson.

  • 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 three separate sessions of same MATLAB.

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

  • In the second session of MATLAB, the Simulink model for flight visualization with Unreal Engine Simulation will be running. This can be skipped if you opt to not add the flight visualization.

  • In the third session of MATLAB, the Simulink model for NVIDIA Jetson communicates with MATLAB on host computer using Monitor & Tune Simulation.

Step 1: Make Hardware Connections and Set Up the Uvify IFO-S Drone in HITL Mode

1. Connect your Autopilot 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.

4. Setup and configure your NVIDIA Jetson on network using MATLAB Coder Support Package for NVIDIA Jetson and NVIDIA DRIVE Platforms.

Tip: Power your NVIDIA Jetson using a separate A/C adapter so that the Autopilot can be independently powered On/Off without rebooting NVIDIA Jetson.

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

The support package includes an example MATLAB project having the PX4 flight controller and the UAV to follow the mission set in the QGroundControl (QGC).

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. Navigate to Navigation subsystem. This is a Variant Subsystem with guidanceType as the variant control variable. Define guidanceType = 1 in the base workspace to choose the navigation subsystem for this example.

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

6. Double click on MAVLink Bridge source and sink blocks and set the serial port of autopilot board.

7. Add a local host connection for flight visualization in MAVLink Bridge Source block. Set the port to 25000.

8. Copy the MATLAB Project Path to clipboard.

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. Select Uvify IFO-S as the Hardware Board.

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 autopilot board.

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: Launch Second Session of MATLAB and Open the Flight Visualization Model

Note: Skip this step if you do not opt for flight visualization with PX4 HITL.

1. Open the second instance of the same MATLAB version. In this MATLAB session, The Simulink model for scenario simulation and flight visualization using unreal environment runs.

Ensure that your Host PC is Configured with MATLAB supported GPU (GPU with compute capability of more than 5).

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. Enable the streaming of simulated depth sensor data in NVIDIA Jetson by updating the variable enableOnboardStreaming to 1.

5. The Simulation 3D Camera block provides the Camera image from the Unreal environment. In this example you stream the depth images from the camera block to NVIDIA Jetson using Video Send block. Double-click block to open the block Parameters dialog box. Add the IP address of onboard computer (NVIDIA Jetson) in the dialog box and click OK.

6. 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: Launch Third Session of MATLAB and the Onboard Model

1. Open the third instance of the same MATLAB version.

2. Navigate to the project path previously copied in Step 2 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 Onboard Algorithm to launch the onboard model named Onboard_Autopilot_Communication.

This model implements the PX4 path planning interface using MAVLink Serializer and MAVLink Deserializer blocks. For more information, see PX4 Path Planning Interface. The MAVLink messages that are exchanged as part of this interface are shown in the following diagram.

5. This example provides a basic onboard logic, which is sending back the received waypoint as the updated waypoint. You can consider designing your own onboard logic after completing this basic example.

6. Navigate to Target hardware resource > Board Parameters, enter the IP address of the NVIDIA Jetson and your login credentials.

7. This example uses MAVLink over serial ports to communicate between the Jetson and autopilot board. Activate serial port variant by setting this workspace variable.

   onboardMAVLinkSource = 1

8. Disable any third party tools that might use the serial ports on Jetson such as MAVLink router.

Open QGC and set the following parameters to use the existing serial link between Jetson and Uvify autopilot. For more information on Uvify serial ports, see Port Numbers for Labels on PX4 Flight Controller Boards.

  • MAV_0_MODE = onboard

  • MAV_0_CONFIG = TELEM1

  • SER_TEL1_BAUD = 230400 8N1

9. Configure the Network Video Receive block to receive the depth data from Unreal environment. Note that the port number and compression parameters in the Network Video Receive block are same as those of the corresponding Video Send block streaming camera image from Unreal engine.

Note: If you do not opt for flight visualization with PX4 HITL, comment the Network Video Receive block.

9. Click Monitor & Tune from Run on Hardware section of Hardware tab in the Simulink Toolstrip.

The code will be generated for the Controller model and the same will be automatically deployed to NVIDIA Jetson. NVIDIA Jetson should start communicating with host over Monitor & Tune Simulation.

Note: Ensure that there are no other deployed models from Simulink are running in NVIDIA Jetson. If you are unable to verify, reboot the Pixhawk hardware board before starting the deployment.

The algorithm in NVIDIA Jetson also communicates with the Plant model UAV_Dynamics_Autopilot_Communication over UDP.

Step 6: 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. Set the PX4 parameter COM_OBS_AVOID enabling the PX4 path planning interface. Navigate to Parameters from the main menu and set the COM_OBS_AVOID parameter value to 1.

3. In the Parameters tab, set the COM_DISARM_PRFLT parameter value to -1.

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

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

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

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

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

8. Start the Mission in QGC. The UAV should follow the mission path.

9. Observe the flight visualization in the Unreal Engine.

10. Go to the Onboard_Autopilot_Communication model and validate the depth image streamed to Jetson during the flight in the Video Viewer (from Computer Vision Toolbox™).

Troubleshooting

  • While Simulating the visualization model in Step 4, you might get any STD exception 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.

  • "Avoidance system not available" warning when starting a mission. This warning occurs because the communication between NVIDIA Jetson and PX4 HITL is not established.

Ensure that host PC and NVIDIA Jetson are connected to same network. Try pinging NVIDIA Jetson from the host PC and vice versa. Also, double-check the NVIDIA Jetson IP address entered in the MAVLink Bridge blocks as mentioned in 6th point of Step 2 and Host PC IP address entered in the UDP send block as mentioned in 7th point of Step 5.