Link Search Menu Expand Document

M0197-FPV Hardware-in-the-Loop Simulation

Table of contents

  1. Overview
    1. Key Differences from Legacy HITL
  2. Sample Repository Structure
  3. System Architecture
    1. Data Flow Summary
      1. Sensor Path (Host -> VOXL2/M0197 DSP)
      2. Actuator Path (VOXL2/M0197 DSP -> Host)
      3. VIO Path (Host -> VOXL2/M0197 Apps Proc)
    2. Data Flow Rates
  4. Component Architecture
    1. Host-Side Components
      1. Gazebo Sim (gz-sim 10 / Jetty)
      2. x500_voxl Vehicle Model
      3. mavlink_hitl_gazebosim Plugin
      4. trajectory_rc_gazebosim Plugin (Optional)
    2. Target-Side Components (Apps Processor)
      1. MavlinkReceiver
      2. voxl-hitl-vio-server
      3. voxl-vision-hub
    3. Target-Side Components (DSP / SLPI)
      1. dsp_hitl Driver
      2. PX4 Flight Stack
  5. uORB Message Definitions
    1. HilSensorImu
    2. HilSensorMagBaro
  6. Startup Sequence
    1. Start Script (under the hood flow)
  7. Network Configuration
    1. Port Allocation
    2. Connection Methods
      1. Option A: ADB Port Forwarding
      2. Option B: Direct USB-Ethernet IP
  8. HITL Default Parameters
    1. System
    2. Sensor Calibration
    3. EKF2
    4. Arming (Relaxed for Simulation)
    5. Control Allocation (X500 Geometry)
  9. Quick Start Guide
    1. Prerequisites
      1. Host PC
      2. VOXL2/M0197
    2. Step-by-Step
      1. 1. Install Gazebo Jetty (Host)
      2. 2. Install Build Dependencies (Host)
      3. 3. Install MAVLink C Headers (Host)
      4. 4. Build Gazebo Plugins (Host)
      5. 5. Build and Deploy voxl-hitl-vio-server (Target)
      6. 6. Build and Deploy voxl-fpv-px4 (Target)
      7. 7. Configure VOXL2/M0197 Services
      8. 8. Connect VOXL2/M0197
      9. 9. Start PX4 HITL on VOXL2/M0197
      10. 10. Launch Gazebo on Host
      11. 11. Verify
      12. 12. Test Flight (PX4 shell)
  10. Verification
    1. Phase 1: Host-side only (no VOXL2 needed)
    2. Phase 2: Target-side pipeline
    3. Phase 3: Full closed-loop
  11. Gazebo Version Compatibility
  12. Headless / Remote Operation
  13. Troubleshooting
    1. Vehicle does not arm
    2. No sensor data received
    3. Motors not spinning in Gazebo
    4. VIO not working
    5. HIL Params not updating:
  14. References

Overview

Hardware-in-the-loop (HITL) simulation enables full-fidelity testing of the PX4 flight stack running on the VOXL2 DSP while the vehicle dynamics are simulated in Gazebo Sim on a host PC. Unlike software-in-the-loop (SITL), HITL exercises the real firmware, real sensor drivers, real EKF2 implementation, and real cross-processor communication paths — providing the highest fidelity simulation short of actual flight.

This document covers the MUORB-based HITL architecture introduced for the M0197-FPV platform, which replaces the legacy FTDI serial approach with UDP-over-USB-Ethernet.

Key advantage: The DSP runs the real flight stack (sensors, EKF2, controllers, commander) exactly as it does in flight. Only the sensor drivers are swapped for HITL shims that receive simulated data from the apps processor via MUORB. The full VOXL2/M0197 software stack is active during HITL — you get the same MPA pipes, mavlink-server telemetry, and VIO integration paths as in real flight.

Key Differences from Legacy HITL

FeatureLegacy (FTDI Serial)Current (UDP-over-USB)
Physical connectionFTDI cable to VOXL2 J18 UARTUSB-C cable (power + network)
Bandwidth~921600 baud (shared with debug console)Full USB-Ethernet (~100 Mbps)
Sensor data routingDirect UART to DSPApps proc MAVLink -> MUORB -> DSP
Apps proc servicesBypassed entirelyFully active (MPA pipes, mavlink-server, VIO)
VFC supportpossible*Native (via voxl-hitl-vio-server + voxl-vision-hub)
FTDI latency tuningRequired (latency_timer sysfs hack)Not needed

Sample Repository Structure

ROOT_DIR/
├── px4-gz-jetty-plugins/   # Gazebo plugins: MAVLink HITL bridge + Trajectory RC
│   ├── src/                # Plugin source (mavlink_hitl_gazebosim, trajectory_rc)
│   ├── worlds/             # Gazebo world files for HITL
│   │   ├── hitl_x500.sdf             # X500 quad HITL world
│   │   └── hitl_x500_trajectory.sdf  # X500 world with trajectory RC automation
│   └── scripts/
│       └── hitl-gz-start.sh          # Launch script for host PC
├── voxl-hitl-vio-server/   # Target-side: receives ODOMETRY UDP, writes MPA pipe
├── voxl-fpv-px4/           # PX4 firmware wrapper (submodule: px4-firmware)
    └── px4-firmware/       # PX4 with HITL startup scripts, dsp_hitl driver, x500_voxl model

System Architecture

The HITL system spans three execution domains: the host PC running Gazebo Sim, the M0197/VOXL2 apps processor (Linux), and the M0197/VOXL2 DSP (Qualcomm SLPI). All inter-device communication uses UDP over the USB-Ethernet link.

HITL System Architecture

Data Flow Summary

Sensor Path (Host -> VOXL2/M0197 DSP)

  1. Gazebo Sim generates simulated sensor readings (IMU at 250 Hz, magnetometer at 50 Hz, barometer at 10 Hz, GPS at 30 Hz) from the x500_voxl vehicle model
  2. mavlink_hitl_gazebosim plugin packs sensor data into MAVLink HIL_SENSOR and HIL_GPS messages, performing ENU/FLU-to-NED/FRD frame rotation at the boundary
  3. Messages are sent via UDP port 14560 over the USB-Ethernet link to the VOXL2/M0197 apps processor
  4. MavlinkReceiver (apps proc) decodes HIL messages and publishes two rate-decoupled uORB topics:
    • hil_sensor_imu at 250 Hz — accelerometer (m/s^2) + gyroscope (rad/s) in body FRD frame
    • hil_sensor_mag_baro at 100 Hz — magnetometer (Gauss) + barometer (Pa) with fields_updated bitmask
  5. MUORB transparently transports these topics from apps proc to DSP
  6. dsp_hitl driver (DSP) subscribes to both topics and republishes them as native PX4 sensor topics (sensor_accel, sensor_gyro, sensor_mag, sensor_baro) with fresh DSP timestamps
  7. VehicleIMU, EKF2, and downstream controllers consume the sensor data identically to real flight

Actuator Path (VOXL2/M0197 DSP -> Host)

  1. PX4 control allocator on DSP computes motor commands and publishes actuator_outputs
  2. HIL_ACTUATOR_CONTROLS MAVLink stream (200 Hz) sends motor commands back to the host via UDP port 14560
  3. mavlink_hitl_gazebosim plugin converts normalized motor commands to rotor velocities and applies them to the Gazebo MulticopterMotorModel joints

VIO Path (Host -> VOXL2/M0197 Apps Proc)

  1. Gazebo SceneBroadcaster publishes ground-truth vehicle pose
  2. mavlink_hitl_gazebosim plugin converts the pose to a MAVLink ODOMETRY message (NED/FRD frame, 250 Hz)
  3. Messages are sent via UDP port 14570 to the VOXL2/M0197 apps processor
  4. voxl-hitl-vio-server (apps proc) decodes the ODOMETRY message and publishes pose data to MPA pipe hitl_vio
  5. voxl-vision-hub (with en_hitl=true) consumes the pipe and runs its VFC control loop, sending SET_ATTITUDE_TARGET commands to PX4

Data Flow Rates

Data PathGz SimMAVLink PluginUDP TransportMavlinkReceiverMUORBdsp_hitl (DSP)PX4 Flight Stack
IMU (accel + gyro)250 Hz250 Hz250 Hz250 Hz250 Hz250 Hz250 Hz
Magnetometer50 Hz50 Hz50 Hz100 Hz (batched)100 Hz50 Hz50 Hz
Barometer10 Hz10 Hz10 Hz100 Hz (batched)100 Hz10 Hz10 Hz
GPS30 Hz30 Hz30 Hz30 Hz30 Hz30 Hz
Actuators (return)200 Hz200 Hz200 Hz200 Hz
VIO (ODOMETRY)250 Hz250 Hz— (to vio-server)— (to VFC)

Notes:

  • IMU: 4 ms publish interval (HIL_IMU_PUBLISH_INTERVAL_US = 4000)
  • MAG/BARO: 10 ms publish interval, fields_updated bitmask tracks which fields are new
  • dsp_hitl polls at 250 Hz (4 ms usleep), republishes with fresh DSP timestamps
  • HIL_ACTUATOR_CONTROLS: flags=0x0F for quad (motors 0-3)

Component Architecture

HITL Component Architecture

Host-Side Components

Gazebo Sim (gz-sim 10 / Jetty)

The simulator runs with a 4 ms physics step (250 Hz real-time update rate) using the ODE physics engine. The world file loads the following system plugins:

PluginPurpose
gz-sim-physics-systemODE physics at 250 Hz
gz-sim-imu-systemAccelerometer + gyroscope
gz-sim-air-pressure-systemBarometric pressure
gz-sim-magnetometer-systemMagnetic field (body frame FLU, use_earth_frame_ned=false)
gz-sim-navsat-systemGPS (spherical coordinates)
gz-sim-scene-broadcaster-systemGround-truth pose for VIO

x500_voxl Vehicle Model

A standalone SDF model derived from the PX4 x500 quadcopter. Includes all sensors on base_link (IMU, barometer, magnetometer, NavSat) and four MulticopterMotorModel plugins for rotor dynamics.

The core HITL bridge plugin. Subscribes to Gz Sim sensor topics, converts frames (ENU/FLU -> NED/FRD), packs MAVLink messages, and sends them to the VOXL2/M0197 over UDP.

Sensor data flow (Gz Sim -> PX4):

MAVLink MessageContentsSource Gz Topic
HIL_SENSORIMU (accel + gyro in FRD), magnetometer, barometerIMU, air_pressure, magnetometer sensors
HIL_GPSGPS fix (lat/lon/alt, velocity, CoG)NavSat sensor
ODOMETRY (optional)VIO pose in NED/FRD for EKF2 external vision fusion/pose/info (SceneBroadcaster)

Actuator data flow (PX4 -> Gz Sim):

MAVLink MessageDescription
HIL_ACTUATOR_CONTROLSMotor commands from PX4’s control allocator, converted to rotor velocities and applied to MulticopterMotorModel joints

Plugin configuration (via SDF <plugin> parameters):

ParameterDefaultDescription
mavlink_addrINADDR_ANYVOXL2/M0197 IP address (e.g. the USB-Ethernet IP)
mavlink_udp_remote_port14560UDP port for HIL messages to PX4
mavlink_udp_local_port0Local bind port (0 = ephemeral)
serialEnabledfalseLegacy serial FTDI mode (not needed)
enable_lockstepfalseSimulation lockstep with PX4
en_vio_outputfalseEnable ODOMETRY output for VIO fusion
vio_mavlink_addrINADDR_ANYTarget IP for VIO messages
vio_udp_remote_port14570UDP port for VIO ODOMETRY messages
vio_update_rate250VIO output rate in Hz
protocol_version2.0MAVLink protocol version

trajectory_rc_gazebosim Plugin (Optional)

A test automation plugin that flies pre-defined trajectories by sending RC_CHANNELS_OVERRIDE MAVLink messages to PX4. State machine: INIT -> ARM -> TAKEOFF -> TRAJECTORY -> HOLD -> LAND -> DISARM -> DONE.

Trajectory format: JSON file with timestamped waypoints in ENU coordinates:

{
  "waypoints": [
    {"t": 0,  "x": 0, "y": 0, "z": 2.0, "yaw": 0},
    {"t": 10, "x": 5, "y": 0, "z": 2.0, "yaw": 0},
    {"t": 20, "x": 5, "y": 5, "z": 3.0, "yaw": 1.57}
  ]
}

The plugin interpolates between waypoints, computes position error, and maps desired velocity to RC stick values via a P-controller. Supports velocity (position control) and attitude (manual/stabilized) control modes.

Target-Side Components (Apps Processor)

MavlinkReceiver

The PX4 MAVLink receiver running on the apps processor. VOXL2-specific code (gated by #if PX4_SOC_ARCH_ID == PX4_SOC_ARCH_ID_VOXL2) handles the HIL sensor bridging:

  • Decodes HIL_SENSOR messages and splits into two rate-decoupled uORB topics
  • Publishes a simulated battery status (16.8V, 5.0A, 100%) at 10 Hz
  • Bridges HIL_GPS to the standard sensor_gps topic

voxl-hitl-vio-server

A standalone service that receives MAVLink ODOMETRY messages on UDP port 14570, extracts pose/velocity/covariance data, and publishes to MPA pipes hitl_vio and hitl_vio_extended. The pipe name hitl_vio (instead of qvio) avoids conflict with the real voxl-qvio-server and matches what voxl-vision-hub expects when en_hitl=true.

Data extracted from ODOMETRY:

  • Position (x, y, z)
  • Orientation (quaternion -> rotation matrix)
  • Linear velocity (vx, vy, vz)
  • Angular velocity (rollspeed, pitchspeed, yawspeed)
  • Pose and velocity covariance diagonals

Configuration (/etc/modalai/voxl-hitl-vio-server.conf):

ParameterDefaultDescription
receiver_ip0.0.0.0Bind address for UDP socket (0.0.0.0 = all interfaces)
receiver_port14570UDP port to listen on (14570 avoids conflict with primary HIL port 14560)

voxl-vision-hub

When configured with en_hitl=true, the vision hub subscribes to the hitl_vio MPA pipe (instead of qvio) and runs its VFC (Vision Flight Controller) control loop during simulation.

Configuration (/etc/modalai/voxl-vision-hub.conf):

{
    "en_vio": false,
    "vio_pipe": "qvio",
    "en_hitl": true,
    "offboard_mode": "vfc"
}
  • en_hitl: true — activates the HITL VIO path in state_manager (subscribes to hitl_vio pipe)
  • offboard_mode: "vfc" — enables the VFC offboard controller

Target-Side Components (DSP / SLPI)

dsp_hitl Driver

The DSP-side HITL shim driver. Polls at 250 Hz for incoming hil_sensor_imu and hil_sensor_mag_baro topics via MUORB and republishes them as native sensor topics with fresh DSP timestamps.

Subscribed TopicPublished TopicsRate
hil_sensor_imusensor_accel, sensor_gyro250 Hz
hil_sensor_mag_baro (FIELD_MAG)sensor_mag50 Hz
hil_sensor_mag_baro (FIELD_BARO)sensor_baro10 Hz

Device IDs (must match calibration parameters):

SensorDevice IDDevice Type
Accelerometer / Gyroscope1310988DRV_IMU_DEVTYPE_SIM
Magnetometer197388DRV_MAG_DEVTYPE_MAGSIM
Barometer6620172DRV_BARO_DEVTYPE_BAROSIM

PX4 Flight Stack

The standard PX4 flight stack runs on the DSP: sensors -> EKF2 -> mc_pos_control -> mc_att_control -> mc_rate_control -> control_allocator. The DSP has no awareness that sensor data originates from simulation.


uORB Message Definitions

Two custom uORB messages transport HIL sensor data from the apps processor to the DSP via MUORB.

HilSensorImu

uint64 timestamp                # time since system start (microseconds)
float32[3] accelerometer_m_s2   # acceleration in body FRD frame (m/s^2)
float32[3] gyroscope_rad_s      # angular velocity in body FRD frame (rad/s)
float32 temperature             # temperature (Celsius)

HilSensorMagBaro

uint64 timestamp                # time since system start (microseconds)
float32[3] magnetometer_ga      # magnetic field in body FRD frame (Gauss)
float32 pressure_pa             # absolute pressure (Pa)
float32 temperature             # temperature (Celsius)
uint8 fields_updated            # bitmask: bit 0 = mag, bit 1 = baro
uint8 FIELD_MAG = 1
uint8 FIELD_BARO = 2

These messages are conditionally compiled: ModalAI boards include HilSensorImu.msg and HilSensorMagBaro.msg while removing OrbTestMedium.msg to stay within the uint8_t ORB_ID enum limit (256 topics).


Startup Sequence

The HITL startup order is critical. MAVLink must be running before dsp_hitl starts, and dsp_hitl must be running before the sensors module starts.

HITL Startup Sequence

Start Script (under the hood flow)

1. Platform detection (M0052 / M0054 / M0104 / M0197)
2. Load HITL default parameters (if first boot)
3. Start apps-proc modules: dataman, navigator, load_mon
4. Start MAVLink instances:
   ├─ Primary   (UDP 14560/14550) — HITL link to Gazebo
   ├─ Secondary (UDP 14556/14557) — voxl-mavlink-server
   └─ Tertiary  (UDP 14558/14559) — GCS forwarding
5. Start dsp_hitl on DSP: qshell dsp_hitl start
6. Wait 1 second (allow MUORB subscriptions to establish)
7. Start sensors on DSP: qshell sensors start -h
8. Start flight stack on DSP: ekf2, controllers, commander
9. Configure MAVLink streams:
   ├─ HIL_ACTUATOR_CONTROLS at 200 Hz (to Gazebo)
   ├─ Disable HIGHRES_IMU, SCALED_IMU (reduce MUORB load)
   └─ Low-rate telemetry: ATTITUDE 10 Hz, GLOBAL_POSITION_INT 5 Hz

Network Configuration

All communication uses UDP over the USB-Ethernet link between the host PC and VOXL2/M0197. No FTDI cable is required.

Port Allocation

PortDirectionProtocolPurpose
14560Host -> VOXL2/M0197MAVLink v2HIL_SENSOR, HIL_GPS
14560VOXL2/M0197 -> HostMAVLink v2HIL_ACTUATOR_CONTROLS (200 Hz)
14570Host -> VOXL2/M0197MAVLink v2ODOMETRY / VIO pose (250 Hz)
14556VOXL2/M0197 localhostMAVLink v2voxl-mavlink-server (onboard)
14558VOXL2/M0197 localhostMAVLink v2GCS forwarding

Connection Methods

Option A: ADB Port Forwarding

adb forward tcp:14560 tcp:14560
adb forward tcp:14570 tcp:14570

Set VOXL2_USB_IP in world SDF to 127.0.0.1. The hitl-gz-start.sh script handles this automatically.

Option B: Direct USB-Ethernet IP

# On VOXL2, find USB network IP:
adb shell ifconfig
# Default VOXL2 USB IP is usually 192.168.101.2 on HOST SIDE

Set VOXL2_USB_IP in world SDF to the discovered IP.


HITL Default Parameters

The HITL parameter configuration (voxl-px4-hitl-set-default-parameters.config) sets PX4 parameters optimized for simulation. Key categories:

System

ParameterValuePurpose
SYS_AUTOSTART1001Generic quadcopter airframe
SYS_HITL1Enable HITL mode globally
IMU_GYRO_RATEMAX800High IMU processing rate

Sensor Calibration

All calibration offsets are zero and scales are 1.0 (identity) since simulated sensors produce ideal data. Device IDs must match the dsp_hitl driver:

ParameterValueMatches
CAL_ACC0_ID1310988DRV_IMU_DEVTYPE_SIM
CAL_GYRO0_ID1310988DRV_IMU_DEVTYPE_SIM
CAL_MAG0_ID197388DRV_MAG_DEVTYPE_MAGSIM

EKF2

ParameterValuePurpose
EKF2_GPS_CHECK0Disable GPS quality gates
EKF2_HGT_REF1GPS as height reference
EKF2_MAG_TYPE1Heading-only mag fusion
EKF2_MAG_CHECK0Disable mag strength validation
EKF2_BARO_CTRL1Enable barometer fusion
EKF2_GPS_CTRL7Full GPS fusion (lon/lat/alt/vel)

Arming (Relaxed for Simulation)

ParameterValuePurpose
CBRK_SUPPLY_CHK894281Bypass supply voltage check
CBRK_IO_SAFETY22027Bypass IO safety switch
COM_ARM_MAG_STR0Disable mag strength gate
COM_ARM_EKF_POS1.0Relaxed EKF position threshold
COM_ARM_EKF_VEL1.0Relaxed EKF velocity threshold

Control Allocation (X500 Geometry)

The rotor positions match the physical x500 frame at +/-0.174m offset:

MotorPosition (X, Y)DirectionKM
0 (Front-Right)+0.174, +0.174CCW+0.05
1 (Back-Left)-0.174, -0.174CCW+0.05
2 (Front-Left)+0.174, -0.174CW-0.05
3 (Back-Right)-0.174, +0.174CW-0.05

Quick Start Guide

Prerequisites

Host PC

  • Ubuntu 24.04
  • Gazebo Jetty (gz-sim 10): sudo apt install gz-jetty
  • MAVLink v2 C headers installed to /usr/include/mavlink/
  • USB cable to VOXL2/M0197

VOXL2/M0197

  • Latest SDK (1.6.2 or newer recommended)
  • voxl-fpv-px4 built with HITL support
  • voxl-hitl-vio-server installed (if using VFC)

Step-by-Step

1. Install Gazebo Jetty (Host)

Follow the official install guide at https://gazebosim.org/docs/jetty/install_ubuntu/ or:

sudo apt-get update
sudo apt-get install curl lsb-release gnupg

sudo curl https://packages.osrfoundation.org/gazebo.gpg --output /usr/share/keyrings/pkgs-osrf-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/pkgs-osrf-archive-keyring.gpg] https://packages.osrfoundation.org/gazebo/ubuntu-stable $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/gazebo-stable.list > /dev/null
sudo apt-get update
sudo apt-get install gz-jetty

2. Install Build Dependencies (Host)

sudo apt-get install \
    build-essential \
    cmake \
    libboost-system-dev \
    libboost-thread-dev \
    libboost-filesystem-dev \
    libeigen3-dev \
    libprotobuf-dev \
    protobuf-compiler \
    libgz-sim-dev \
    libgz-plugin-dev \
    libgz-sensors-dev \
    libgz-msgs-dev \
    libgz-cmake3-dev
# Clone MAVLink with pymavlink submodule
git clone https://github.com/mavlink/mavlink.git --recursive

# Install pymavlink dependencies
pip3 install --break-system-packages -r mavlink/pymavlink/requirements.txt

# Generate C headers for the development dialect
cd mavlink
python3 -m pymavlink.tools.mavgen \
    --lang=C \
    --wire-protocol=2.0 \
    --output=generated/include/mavlink/v2.0 \
    message_definitions/v1.0/development.xml

# (OPTIONAL) Install system-wide
sudo cp -r generated/include/mavlink /usr/include/
cd ..

Verify: ls /usr/include/mavlink/v2.0/common/mavlink.h

4. Build Gazebo Plugins (Host)

cd px4-gz-jetty-plugins
mkdir -p build && cd build
cmake ..
make -j$(nproc)

This produces build/libmavlink_hitl_gazebosim.so and build/libtrajectory_rc_gazebosim.so.

Or via Docker:

docker build -t px4-gz-jetty-plugins .
docker create --name tmp px4-gz-jetty-plugins
docker cp tmp:/artifacts/. ./build/
docker rm tmp

5. Build and Deploy voxl-hitl-vio-server (Target)

cd voxl-hitl-vio-server
voxl-docker -i voxl-cross
# Inside docker:
./install_build_deps.sh $BOARD_SOC dev
./build.sh $BOARD_SOC
./make_package.sh
exit
# RUN THE FOLLOWING OUTSIDE OF THE DOCKER CONTAINER --(DEPENDING ON PERMISSIONS)
./deploy_to_voxl.sh

6. Build and Deploy voxl-fpv-px4 (Target)

cd voxl-fpv-px4
./run_docker.sh
./build.sh
./make_package.sh
# RUN THE FOLLOWING OUTSIDE OF THE DOCKER CONTAINER --(DEPENDING ON PERMISSIONS)
./deploy_to_voxl.sh

7. Configure VOXL2/M0197 Services

On the VOXL2/M0197, configure voxl-hitl-vio-server (/etc/modalai/voxl-hitl-vio-server.conf):

{
    "receiver_ip": "0.0.0.0",
    "receiver_port": 14570
}

Configure voxl-vision-hub (/etc/modalai/voxl-vision-hub.conf):

{
    "en_vio": false,
    "vio_pipe": "qvio",
    "en_hitl": true,
    "offboard_mode": "vfc"
}

8. Connect VOXL2/M0197

Connect the VOXL2/M0197 via USB-C. Verify connectivity:

ping 192.168.101.2
# or use ADB:
adb devices

9. Start PX4 HITL on VOXL2/M0197

# Terminal 1
adb shell
voxl-px4-hitl start

# Terminal 2
# Start VIO server and vision hub
adb shell
systemctl start voxl-hitl-vio-server
systemctl start voxl-vision-hub

10. Launch Gazebo on Host

cd px4-gz-jetty-plugins

# With ADB port forwarding (default, VOXL2/M0197 connected via USB)
./scripts/hitl-gz-start.sh

# With direct USB network IP
./scripts/hitl-gz-start.sh -i 192.168.101.2

# With trajectory automation
./scripts/hitl-gz-start.sh -i 192.168.101.2 -t /path/to/trajectory.json

The script:

  • Sets GZ_SIM_SYSTEM_PLUGIN_PATH to the plugin build directory
  • Sets GZ_SIM_RESOURCE_PATH to include PX4 vehicle models (x500_voxl)
  • Substitutes the VOXL2/M0197 IP into the world file’s VOXL2_USB_IP placeholder
  • Sets up adb forward tcp:14570 tcp:14570 if using localhost
  • Launches gz sim with the HITL world

Or manually:

export GZ_SIM_SYSTEM_PLUGIN_PATH=/path/to/px4-gz-jetty-plugins/build
export GZ_SIM_RESOURCE_PATH=/path/to/voxl-fpv-px4/px4-firmware/Tools/simulation/gz/models
gz sim worlds/hitl_x500.sdf -v 4

11. Verify

On the VOXL2/M0197 PX4 shell after the startup HIL script runs:

px4> qshell dsp_hitl status

Expected output showing incrementing counters:

Running: yes
=== IMU Section ===
  HIL sensor_imu received: 12453
  IMU updates published: 12450
  Current accel (x,y,z): -0.257, 0.151, -9.859
  Current gyro (x,y,z): -0.006, -0.001, 0.000
=== MAG/BARO Section ===
  HIL sensor_mag_baro received: 4980
  MAG updates published: 4975
  BARO updates published: 995

Verify VIO data: (Regular VOXL shell)

voxl-inspect-pipes
# Look for "hitl_vio" pipe with data
voxl-inspect-vio hitl_vio

12. Test Flight (PX4 shell)

px4> qshell commander arm
px4> qshell commander takeoff
# Observe vehicle in Gazebo
px4> qshell commander land

Verification

Phase 1: Host-side only (no VOXL2 needed)

# Terminal 1: start gz-sim
cd px4-gz-jetty-plugins
./scripts/hitl-gz-start.sh

# Terminal 2: listen for ODOMETRY on port 14570
python3 -c "
import socket
sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
sock.bind(('0.0.0.0', 14570))
while True:
    data, addr = sock.recvfrom(1024)
    print(f'Received {len(data)} bytes from {addr}')
"

You should see packets arriving at ~250 Hz.

Phase 2: Target-side pipeline

  1. Start voxl-hitl-vio-server on VOXL2
  2. Send ODOMETRY from host via gz-sim
  3. Verify hitl_vio MPA pipe has data: voxl-inspect-pipes on VOXL2

Phase 3: Full closed-loop

  1. Start PX4 HITL on VOXL2 (voxl-px4-hitl start)
  2. Start gz-sim on host (hitl-gz-start.sh)
  3. Verify VFC engages when RC channels are in range
  4. Test position hold — drone should hover stably

Gazebo Version Compatibility

This plugin stack is configured for Gazebo Jetty (gz-sim 10.x). The CMakeLists.txt uses unversioned cmake package names (gz-sim, gz-plugin, gz-sensors), which is the convention for Gazebo Jetty/Ionic.

For older Gazebo versions, update px4-gz-jetty-plugins/CMakeLists.txt:

Gazebo Versiongz-simgz-plugingz-sensorsgz-msgs
Gardengz-sim7gz-plugin2gz-sensors7gz-msgs9
Harmonicgz-sim8gz-plugin2gz-sensors8gz-msgs10
Ionicgz-sim9gz-plugin3gz-sensors9gz-msgs11
Jettygz-sim (10)gz-plugin (4)gz-sensors (10)gz-msgs (12)

For versioned releases (Garden/Harmonic/Ionic), use versioned find_package() calls and target names (e.g., gz-sim8::gz-sim8).


Headless / Remote Operation

Gz Sim can run fully headless for CI/automated testing:

gz sim -s -r <world.sdf>   # server-only, no GUI, start running

Troubleshooting

Vehicle does not arm

  • Verify dsp_hitl status shows increasing counters
  • Check EKF2 is fusing: listener estimator_status on PX4 shell
  • Ensure sensor device IDs match calibration parameters
  • Check commander status for preflight check failures

No sensor data received

  • Verify Gazebo is running and not paused (WorldControl widget)
  • Check UDP connectivity: netstat -un | grep 14560
  • Verify MAVLink instance is running: mavlink status on PX4 shell
  • Ensure hitl-gz-start.sh resolved the correct VOXL2 IP

Motors not spinning in Gazebo

  • Verify HIL_ACTUATOR_CONTROLS stream is configured at 200 Hz
  • Check msg.flags = 0x0F is set (VOXL2 quad bitmask)
  • Ensure the x500_voxl model does not have <robotNamespace/> tags in motor plugins

VIO not working

  • Verify voxl-hitl-vio-server is running: systemctl status voxl-hitl-vio-server
  • Check MPA pipe: voxl-inspect-pipes should show hitl_vio
  • Verify voxl-vision-hub has en_hitl=true in config

HIL Params not updating:

  • Remove HIL params on /data/px4/param directory
  • (Caution)
    cd /data/px4/param && rm hitl*
    # Now run again
    voxl-px4-hitl
    

References