Main Content

Speedgoat and Simulink Real-Time Setup

This topic helps you with setting up Speedgoat® and Simulink® Real-Time™ for PX4 Autopilot in Hardware-in-the-Loop (HITL) Simulation with Speedgoat in Simulink example. Hardware-in-the-loop simulation allows you to validate your controller design code running on an embedded system in normal and adverse real-world conditions.

The following image shows an overview of hardware connections and information flow between PX4 Autopilot, Speedgoat, and QGC.

Information flow

In the PX4 Autopilot in Hardware-in-the-Loop (HITL) Simulation with Speedgoat in Simulink example, a quadcopter plant model, along with its sensors, are modeled in Simulink. The generated code is deployed to Speedgoat Real-Time Target machines to perform HITL simulation. The example demonstrates the following workflows.

  • Real-Time simulation of plant and sensors in Speedgoat.

  • Controller deployment to PX4 Autopilot.

  • Photorealistic simulation using unreal engine, based on plant states obtained from Speedgoat.

  • Running an obstacle avoidance algorithm on Jetson™ using the depth camera data simulated in Unreal Engine.

The plant model communicates with PX4 Autopilot to share the sensor and actuator data. The plant model additionally shares the UAV ground truth (position and orientation) to host PC running photorealistic simulation.

The photorealistic simulator provides a 3D visualization of the UAV’s movement along with simulating its depth camera. Depth data is sent over to a Jetson onboard computer running an obstacle avoidance algorithm, which corrects the path accounting for any obstacles and sends back corrected path over to PX4 Autopilot.

Required Hardware

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

  • Speedgoat Baseline with IO397 module

  • IO397 Terminal board

  • A supported PX4 Autopilot board with a class 10 microSD card.

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

  • USB to Ethernet converter

  • Pixhawk® UART to jumper male converter

  • 2 x FTDI units

To run onboard obstacle avoidance, you need the following,

  • Jetson Xavier / Nano connected to autopilot over UART

Make Connections for Speedgoat

Connect the hardware as shown in this diagram. You can skip the Jetson connection if you are not running onboard obstacle avoidance.

Information flow

A sample image of Speedgoat connected to PX4 Autopilot, QGC, host computer is shown below.

Connect Speedgoat

Connect the following ports between Pixhawk and Speedgoat's IO397 Terminal board.

Pixhawk Speedgoat connections

Pixhawk (GPS)IO397 Terminal board
Tx16b
Rx15b
GND17b

Pixhawk GPS 1 port is connected to IO397 Terminal board.

To establish a connection with unreal visualization model, perform these steps.

  1. connect a FTDI port to the right USB port.

  2. Connect the TX of FTDI to RX of another FTDI and vice-versa. Also connect gnd.

  3. Connect the second FTDI unit to host PC that runs unreal visualization model.

Speedgoat Configuration

To configure the Serial ports and IO397 module, refer to the following image. If you have a different Speedgoat configuration such as a different IO module, then use this information to configure Speedgoat. Serial ports and IO397 modules are available in Speedgoat Setup section of Simulink plant model (UAV_Dynamics_Speedgoat). For more information on opening the Simulink model, see PX4 Autopilot in Hardware-in-the-Loop (HITL) Simulation with Speedgoat in Simulink.

Speedgoat configuration

Software Setup

Along with the required products mentioned in the example, you must also download and install the following software.

Create an account in Speedgoat to download and install the Simulink IO Blockset and IO397 configuration package.

For more information, see Speedgoat Software.

Connections for Speedgoat

  1. Connect the Speedgoat machine to host computer over an Ethernet-USB converter.

  2. Depending on the operating system installed on the host computer, use the links provided below to configure your network adapter to communicate with Speedgoat.

  3. Open slrtExplorer and follow these instructions to configure the IP address and update the firmware of Speedgoat.

  4. If you are not yet connected to the target computer, click Disconnected to change it to Connected.

PX4 Parameter Setup in QGC

Set the parameters values in QGroundControl (QGC), as shown in the table below.

QGC Parameters

ParameterValue
SER_GPS1_BAUD921600 8N1
SER_TEL1_BAUD230400 8N1
MAV_0_CONFIGTELEM 1
MAV_0_FORWARD1
MAV_0_MODEOnboard
MAV_0_RADIO_CTL1
MAV_0_RATE1200 B/s
MAV_1_CONFIGGPS1
MAV_1_FORWARD0
MAV_1_MODEConfig
MAV_1_RATE0 B/s

See Also