PX4 Simulation in Hardware (SIH)
Table of contents
- Introduction
- Starting SIH on VOXL Boards
- Quick Start
- Default Parameters
- Limitations
- Troubleshooting
- References
Introduction
Simulation in Hardware (SIH) is a lightweight, self-contained flight simulation that runs entirely on the flight controller. Unlike HITL which requires an external host PC running Gazebo, SIH uses a built-in rigid body dynamics model to generate simulated sensor data directly on the board. No external simulator, cables, or network connection are needed.
SIH is useful for quick validation of flight logic, controller tuning, and parameter testing without needing to set up a full Gazebo simulation environment. The full PX4 flight stack (EKF2, controllers, commander) runs exactly as it does in real flight — only the sensor drivers are replaced by the physics model.
Please refer to the official PX4 documentation for more details: https://docs.px4.io/main/en/sim_sih/
SIH vs. HITL vs. SITL
| Feature | SIH | HITL | SITL |
|---|---|---|---|
| Where simulation runs | On the flight controller | External host PC (Gazebo) | Host PC (no flight controller) |
| Hardware required | Flight controller only | Flight controller + host PC + USB/FTDI | Host PC only |
| PX4 execution | Real firmware on real hardware | Real firmware on real hardware | Compiled natively on host |
| Sensor fidelity | Simplified physics model | High-fidelity Gazebo sensors | High-fidelity Gazebo sensors |
| Visual output | None (telemetry only) | Gazebo 3D rendering | Gazebo 3D rendering |
| Setup complexity | Minimal | Moderate | Moderate |
| Best for | Controller tuning, quick validation | Full system testing with VIO/camera | Algorithm dev on host |
Starting SIH on VOXL Boards
On VOXL platforms, SIH is started using the -S (uppercase) flag on the voxl-px4 script:
voxl-px4 -S
This is analogous to how HITL is started with voxl-px4 -s (lowercase). The -S flag launches PX4 with the SIH-specific startup script (voxl-px4-sih-start).
Startup Sequence
When voxl-px4 -S is invoked, the following happens:
Default parameters are loaded from
/etc/modalai/voxl-px4-sih-set-default-parameters.config(on first run) or from the saved parameter file at/data/px4/param/sih_parameters(on subsequent runs)- Simulated sensor drivers start on the DSP via
qshell:simulator_sih— the core physics simulationsensor_baro_sim— simulated barometersensor_gps_sim— simulated GPSsensor_mag_sim— simulated magnetometerpwm_out_sim— simulated PWM output
- Flight stack modules start on DSP:
sensors,ekf2mc_pos_control,mc_att_control,mc_rate_controlmc_hover_thrust_estimator,mc_autotune_attitude_controlland_detector,manual_control,control_allocator,rc_updatecommander,flight_mode_manager
- Apps processor modules start:
dataman,navigatorvehicle_air_data_bridge,sensor_baro_bridge,vehicle_local_position_bridgesih_vio_bridge— bridges SIH ground truth for VIO consumers
ROS 2 interface starts via
uxrce_dds_client(UDP on port 8888)- MAVLink links start:
- Onboard fast link on UDP 14556/14557 for
voxl-mavlink-server - Normal link on UDP 14558/14559 for GCS forwarding
- Visualization stream on UDP 14560 with
HIL_STATE_QUATERNIONat 200 Hz (for jMAVSim or other external viewers)
- Onboard fast link on UDP 14556/14557 for
- Logger starts based on the
SDLOG_MODEparameter
NOTE: Unlike the upstream PX4 rcS-based boot (which uses SYS_HITL=2 and airframe files like 1100_rc_quad_x_sih.hil), VOXL boards use the voxl-px4 wrapper script to manage the startup sequence directly.
Quick Start
1. Start SIH
voxl-px4 -S
On first run, default SIH parameters will be written to /data/px4/param/sih_parameters. On subsequent runs, parameters are loaded from this file.
2. Verify SIH is Running
Confirm the simulator and simulated sensors are publishing data:
listener sensor_accel # should show updating accel data
listener sensor_gyro # should show updating gyro data
listener sensor_baro # should show barometer readings
3. Connect QGroundControl
Connect QGroundControl via MAVLink (through voxl-mavlink-server). You should see the vehicle on the map at the simulated GPS location and the attitude indicator should be active.
4. Arm and Fly
Arm and take off via QGroundControl or the MAVLink shell:
commander arm
commander takeoff
The vehicle will take off and hover in the simulated environment. Use QGroundControl’s attitude indicator, map view, and telemetry widgets for feedback since there is no 3D visual rendering.
Optional: jMAVSim Visualization
The SIH startup script configures a MAVLink visualization stream on UDP port 14560 with HIL_STATE_QUATERNION at 200 Hz. You can connect jMAVSim or another external viewer to this stream for a 3D visualization of the simulated vehicle. The default target IP is 192.168.101.1 — adjust this in the startup script if needed.
Default Parameters
The SIH default parameter configuration (voxl-px4-sih-set-default-parameters.config) sets up the following on first run:
Airframe and Calibration
| Parameter | Value | Description |
|---|---|---|
SYS_AUTOSTART | 4001 | Quadrotor X airframe |
CAL_ACC0_ID | 1310988 | Simulated accelerometer (DRV_IMU_DEVTYPE_SIM) |
CAL_GYRO0_ID | 1310988 | Simulated gyroscope (DRV_IMU_DEVTYPE_SIM) |
CAL_MAG0_ID | 197388 | Simulated magnetometer |
MAV_TYPE | 2 | Quadrotor |
Control Allocation
| Parameter | Value | Description |
|---|---|---|
CA_AIRFRAME | 0 | Multicopter |
CA_ROTOR_COUNT | 4 | Quadrotor |
HIL_ACT_FUNC1–4 | 101–104 | Motor function mapping for pwm_out_sim |
Safety Bypasses
| Parameter | Value | Purpose |
|---|---|---|
CBRK_SUPPLY_CHK | 894281 | Bypass battery check (no real battery in SIH mode) |
Parameters are saved to /data/px4/param/sih_parameters and persist across reboots. To reset to defaults, delete this file and restart:
rm /data/px4/param/sih_parameters
voxl-px4 -S
Limitations
- No visual output — SIH does not provide 3D rendering on its own. Use QGroundControl for telemetry feedback, or connect jMAVSim to the visualization stream on UDP 14560. Flights can also be logged and analyzed with FlightReview.
- Simplified physics — The rigid body model does not capture complex effects like ground effect, turbulence, rotor wake interaction, or detailed aerodynamic nonlinearities.
- No camera or VIO simulation — SIH does not generate simulated images. For VIO testing, use HITL with Gazebo.
- No environment interaction — There are no obstacles, wind, or terrain beyond a flat ground plane.
- Single vehicle only — One simulated vehicle per flight controller instance.
Troubleshooting
Resetting parameters
If parameters get into a bad state, delete the saved parameter file and restart:
rm /data/px4/param/sih_parameters
voxl-px4 -S
References
- PX4 SIH Documentation
- VOXL2 PX4 HITL Setup — for full-fidelity simulation with Gazebo