| Target | Autostart | Simulator | What it does |
|---|---|---|---|
jmavsim / jmavsim_iris |
10017 | jMAVSim (physics + viz) | Builds jMAVSim jar, launches PX4 + jMAVSim together |
none |
(none, uses saved params) | None | Launches bare PX4, no simulator |
none_iris |
10016 | None | Launches PX4 with Iris airframe, no simulator |
sihsim_quadx |
(env-based) | SIH | PX4 with built-in quad physics |
sihsim_airplane |
(env-based) | SIH | PX4 with fixed-wing physics |
sihsim_xvert |
(env-based) | SIH | PX4 with tailsitter physics |
sihsim_standard_vtol |
(env-based) | SIH | PX4 with standard VTOL physics |
sihsim_hex |
(env-based) | SIH | PX4 with hexacopter physics |
sihsim_rover_ackermann |
(env-based) | SIH | PX4 with rover physics |
-
build_jmavsim: Builds the jMAVSim JAR via
ant create_run_jar copy_res- Depends on:
git_jmavsim,jmavsim_run_symlink - Output:
Tools/simulation/jmavsim/jMAVSim/out/production/jmavsim_run.jar
- Depends on:
-
jmavsim_run_symlink: Creates symlink to
jmavsim_run.shin rootfs -
jmavsim_iris: Launch helper, sets
PX4_SYS_AUTOSTART=10017- Depends on:
px4,git_jmavsim,build_jmavsim,jmavsim_run_symlink
- Depends on:
-
jmavsim: Alias for
jmavsim_iris
Build requirements: Java ANT, javac, java (all must be the same Java version)
Single airframe: 10017_jmavsim_iris (3DR Iris Quadrotor, Quadrotor Wide, 4 rotors in X config)
| Class | Rotors | Notes |
|---|---|---|
Quadcopter |
4 | Supports "x" and "+" layouts, "default" and "cw_fr" rotor positions |
Hexacopter |
6 | Supports "x" and "+" orientations |
Inheritance: AbstractVehicle -> AbstractMulticopter -> Quadcopter / Hexacopter
No fixed-wing, VTOL, or rover physics exist in jMAVSim.
| Flag (script) | Flag (java) | Model file | Vehicle shown |
|---|---|---|---|
| (default) | -mc |
models/3dr_arducopter_quad_x.obj |
Quadcopter |
-a |
-fw |
models/cessna.obj |
Fixed-wing |
-t |
-ts |
models/x_vert.obj |
Tailsitter |
These only change the rendered 3D model. They do not change physics.
| Flag | Java arg | Description |
|---|---|---|
-l |
-lockstep |
Lockstep mode |
-r <Hz> |
-r <Hz> |
Update rate |
-p <port> |
port in device string | Connection port |
-u |
-udp |
Use UDP instead of TCP |
-i <ip> |
ip in device string | IP address |
-o |
-disponly |
Display only (no physics, just rendering) |
-a |
-fw |
Show fixed-wing model |
-t |
-ts |
Show tailsitter model |
-q |
-qgc |
QGC forwarding |
-s |
-sdk |
SDK mode |
HEADLESS=1 |
-no-gui |
No GUI window |
-b <baud> |
serial baudrate | For serial connections |
-d <dev> |
serial device | Serial device path |
Views:
F- First-person view (follows vehicle)S- Stationary ground cameraG- Gimbal cameraZ- Toggle auto-zoom for stationary camera+/-- Zoom in/out0/ENTER- Reset zoom
Actions:
Q- Disable sim on MAVI- Enable sim on MAVH- Toggle HUD overlayC- Clear HUD messagesR- Toggle data report sidebarT- Toggle data report updatesD- Toggle sensor parameter control sidebarF1- Key commands referenceP- Pause simulationESC- Exit jMAVSimSPACE- Reset vehicle and view
Vehicle Manipulation:
- Arrow keys - Rotate pitch/roll
END/PG-DN- Rotate yawSHIFT + arrows- Move N/S/E/WSHIFT + INS/DEL- Move up/down- Numpad 8/2/4/6 - Rotation rate around pitch/roll
- Numpad 1/3 - Rotation rate around yaw
- Numpad 5 - Stop all rotation
CTRL + Numpad 5- Reset attitude/velocity/acceleration
Incoming (Simulator to PX4):
HIL_SENSOR(ID 107) - IMU, mag, baro, differential pressure with timestampHIL_GPS(ID 113) - GPS position, velocity, headingHIL_OPTICAL_FLOW(ID 100) - Optical flow data
Outgoing (PX4 to Simulator):
HIL_ACTUATOR_CONTROLS(ID 93) - Motor PWM and control surface outputs
- Only multicopter physics (Quad/Hex). No fixed-wing, VTOL, or rover.
- Single airframe (10017 Iris quad)
- Java version mismatch issues on macOS (
antvsjavamay use different JDKs) - Stale jar cache if compiled with wrong Java version (must
rm -rf Tools/simulation/jmavsim/jMAVSim/out) - 3D model swap (
-fw,-ts) is cosmetic only, does not change physics - Slow startup (JVM + ant build)
- Community supported, may be removed in future releases
On macOS with multiple Java versions via Homebrew, ant and java may resolve to different JDKs:
antdefaults to/opt/homebrew/opt/openjdk(could be Java 25)javavia/usr/bin/javaresolves toopenjdk@17
Fix: always set JAVA_HOME before running:
export JAVA_HOME=$(/usr/libexec/java_home -v 17)SIH is a built-in C++ simulator that runs inside PX4 itself. Originally designed for real flight controllers ("Simulator in Hardware"), it now also works as a SITL simulator with zero external dependencies.
Controlled by SIH_VEHICLE_TYPE parameter:
| Type | Enum | Physics Model | Supported Since |
|---|---|---|---|
| Quadcopter | 0 | 4 rotors, rigid body dynamics | v1.9 |
| Fixed-wing | 1 | Aerodynamic segments (Khan 2016 PhD thesis), 1 motor + 3 control surfaces | v1.13 |
| Tailsitter VTOL | 2 | 11 aerodynamic segments (Chiappinelli 2018), 2 rotors + 2 surfaces | v1.13 |
| Standard VTOL | 3 | Blended quad + FW dynamics, 5 rotors + 3 surfaces | v1.16 |
| Hexacopter | 4 | 6 rotors, symmetric X | v1.17 |
| Rover Ackermann | 5 | Bicycle model, steering + throttle | v1.17 |
| Airframe ID | File | Vehicle |
|---|---|---|
| 10040 | 10040_sihsim_quadx |
Quadcopter X |
| 10041 | 10041_sihsim_airplane |
Fixed-wing |
| 10042 | 10042_sihsim_xvert |
Tailsitter |
| 10043 | 10043_sihsim_standard_vtol |
Standard VTOL |
| 10044 | 10044_sihsim_hex |
Hexacopter |
| 10045 | 10045_sihsim_rover_ackermann |
Rover Ackermann |
rcS-posix
-> PX4_SIM_MODEL env var selects SYS_AUTOSTART
-> airframe file sets PX4_SIMULATOR=sihsim
-> px4-rc.simulator dispatches to px4-rc.sihsim
-> simulator_sih start
-> conditional sensor_*_sim starts (based on SENS_EN_*SIM params)
Dispatcher logic (px4-rc.simulator):
if PX4_SIMULATOR=sihsim OR SYS_AUTOSTART=0 --> px4-rc.sihsim
elif PX4_SIMULATOR=gz OR SIM_GZ_EN=1 --> px4-rc.gzsim
elif PX4_SIM_MODEL=jmavsim_iris OR AUTOSTART=10017 --> px4-rc.jmavsim
else --> px4-rc.mavlinksimPhysical model:
SIH_MASS- Vehicle mass (kg), default 1.0SIH_IXX/IYY/IZZ- Diagonal inertia (kg m^2)SIH_IXY/IXZ/IYZ- Off-diagonal inertiaSIH_T_MAX- Max propeller thrust (N), default 5.0SIH_Q_MAX- Max propeller torque (Nm), default 0.1SIH_L_ROLL/L_PITCH- Arm lengths (m), default 0.2
Aerodynamics:
SIH_KDV- First-order drag coefficient, default 1.0SIH_KDW- Angular damper coefficient, default 0.025SIH_T_TAU- Thruster time constant (s), default 0.05
Geographic/environmental:
SIH_LOC_LAT0- Initial latitude (deg), default 47.397742SIH_LOC_LON0- Initial longitude (deg), default 8.545594SIH_LOC_H0- Initial AMSL altitude (m), default 489.4
Sensors:
SIH_DISTSNSR_MIN/MAX- Distance sensor range limitsSIH_DISTSNSR_OVR- Distance sensor override (-1 = disabled)
| Sensor | Rate | Module | Parameter |
|---|---|---|---|
| IMU (accel + gyro) | 250 Hz | Built into SIH | Always on |
| Barometer | Configurable | sensor_baro_sim |
SENS_EN_BAROSIM |
| GPS | Configurable | sensor_gps_sim |
SENS_EN_GPSSIM |
| Magnetometer | Configurable | sensor_mag_sim |
SENS_EN_MAGSIM |
| Airspeed | 50 Hz | Built into SIH | For FW/VTOL types |
| Distance sensor | 50 Hz | Built into SIH | SIH_DISTSNSR_* params |
Ground truth publications (for logging/analysis):
vehicle_angular_velocity_groundtruthvehicle_attitude_groundtruthvehicle_local_position_groundtruthvehicle_global_position_groundtruth
PX4_SIM_SPEED_FACTOR=10 make px4_sitl sihsim_quadxUses lockstep scheduler for deterministic, faster-than-realtime simulation.
SIH runs on the flight controller itself. The FC runs the full PX4 stack with simulated sensors instead of real ones. You can connect an RC transmitter and fly without a real vehicle.
Trigger: SYS_HITL=2 (0 = normal, 1 = external HITL, 2 = SIH)
rcS -> SYS_HITL=2 check
-> sensors start -h (HITL mode, disables real sensors)
-> param set GPS_1_CONFIG 0 (disable real GPS)
-> simulator_sih start
-> sensor_baro_sim start
-> sensor_mag_sim start
-> sensor_gps_sim start
-> sensor_agp_sim start
| Airframe ID | File | Vehicle | SIH Type |
|---|---|---|---|
| 1100 | 1100_rc_quad_x_sih.hil |
Quadcopter X | 0 |
| 1101 | 1101_rc_plane_sih.hil |
Fixed-wing | 1 |
| 1102 | 1102_tailsitter_duo_sih.hil |
Tailsitter | 2 |
| 1103 | 1103_standard_vtol_sih.hil |
Standard VTOL | 3 |
| 1104 | 1104_standard_ackermann_sih.hil |
Rover Ackermann | 5 |
Note: No hexacopter hardware airframe (type 4), though the SIH engine supports it.
| Aspect | Hardware (FC) | SITL |
|---|---|---|
| Trigger | SYS_HITL=2 |
PX4_SIMULATOR=sihsim env var |
| Actuator params | HIL_ACT_FUNC* |
PWM_MAIN_FUNC* |
| Sensor startup | Auto-enabled by rcS | Manual via SENS_EN_*SIM params |
| Timing | Real-time 250 Hz loop | Lockstep (supports speed factor) |
| Speed control | None (real-time only) | PX4_SIM_SPEED_FACTOR |
| GPS delay | Default (realistic) | 0 (instant) |
| Airframes dir | init.d/airframes/ |
init.d-posix/airframes/ |
Config symbol: CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
53 hardware boards have SIH enabled by default. Notable ones:
| Board | Config File |
|---|---|
| px4/fmu-v5 | boards/px4/fmu-v5/default.px4board |
| px4/fmu-v5x | boards/px4/fmu-v5x/default.px4board |
| px4/fmu-v6x | boards/px4/fmu-v6x/default.px4board |
| px4/fmu-v6c | boards/px4/fmu-v6c/default.px4board |
| holybro/durandal-v1 | boards/holybro/durandal-v1/default.px4board |
| cuav/x7pro | boards/cuav/x7pro/default.px4board |
| ark/fmu-v6x | boards/ark/fmu-v6x/default.px4board |
| emlid/navio2 | boards/emlid/navio2/default.px4board |
| beaglebone/blue | boards/beaglebone/blue/default.px4board |
Not supported: FMUv2 (too resource-constrained)
Enabling SIH in Kconfig auto-selects:
pwm_out_sim- simulated PWM outputsensor_baro_sim- simulated barometersensor_gps_sim- simulated GPSsensor_mag_sim- simulated magnetometer
jMAVSim via serial USB (display-only):
# Linux
./Tools/simulation/jmavsim/jmavsim_run.sh -q -d /dev/ttyACM0 -b 2000000 -o
# macOS
./Tools/simulation/jmavsim/jmavsim_run.sh -q -d /dev/tty.usbmodem1 -b 2000000 -o
# Add -a for fixed-wing model, -t for tailsitter modelOr just use QGroundControl directly. No visualizer required.
| Aspect | jMAVSim (standalone) | SIH (SITL) | SIH (on hardware) |
|---|---|---|---|
| Dependencies | Java, ANT | None | Flight controller |
| Vehicle types | Quad, Hex (physics). FW/TS (display only) | 6 types with full physics | 5 types (no hex airframe) |
| Physics engine | Java, rotor-only | C++, full aero models | Same C++ engine |
| Startup time | Slow (JVM + ant) | Fast (built-in module) | Instant (on boot) |
| CPU usage | Moderate (GUI), low (headless) | Very low | Runs on FC MCU |
| Data path | MAVLink HIL_SENSOR/HIL_ACTUATOR | Direct uORB topics | Direct uORB topics |
| Lockstep | Via MAVLink | Built-in scheduler | N/A (real-time) |
| Speed factor | No | Yes (PX4_SIM_SPEED_FACTOR) |
No (real-time only) |
| Visualization | Built-in 3D GUI | Optional (jMAVSim -o or QGC) |
Optional (jMAVSim -o or QGC) |
| RC input | Via QGC/joystick | Via QGC/joystick | Real RC transmitter |
| Sensor fidelity | Basic noise | Comprehensive (noise, delay, all types) | Same as SITL |
| Ground truth | No | Yes (uORB topics) | Yes (uORB topics) |
| Use case | Quick quad testing | Development, CI, rapid prototyping | Pilot training, HW validation |
SIH handles all physics internally. jMAVSim provides optional 3D visualization in display-only mode (-o). This gives the best of both worlds: accurate multi-vehicle-type physics from SIH with visual feedback from jMAVSim.
SITL:
# Terminal 1: jMAVSim display-only
./Tools/simulation/jmavsim/jmavsim_run.sh -p 19410 -u -q -o # quad
./Tools/simulation/jmavsim/jmavsim_run.sh -p 19410 -u -q -o -a # fixed-wing model
./Tools/simulation/jmavsim/jmavsim_run.sh -p 19410 -u -q -o -t # tailsitter model
# Terminal 2: PX4 with SIH
make px4_sitl sihsim_quadx
make px4_sitl sihsim_airplane
make px4_sitl sihsim_xvertOn hardware:
# On desktop, connected to FC via USB
./Tools/simulation/jmavsim/jmavsim_run.sh -q -d /dev/ttyACM0 -b 2000000 -oLimitation: jMAVSim always shows the same 3D model regardless of SIH vehicle type unless you manually pass -a (fixed-wing) or -t (tailsitter). There is no automatic model switching.
jMAVSim:
Tools/simulation/jmavsim/jmavsim_run.sh- Launch scriptTools/simulation/jmavsim/jMAVSim/src/me/drton/jmavsim/Simulator.java- Main entryTools/simulation/jmavsim/jMAVSim/src/me/drton/jmavsim/vehicle/- Vehicle classessrc/modules/simulation/simulator_mavlink/sitl_targets_jmavsim.cmake- CMake targetssrc/modules/simulation/simulator_mavlink/SimulatorMavlink.cpp- MAVLink bridgeROMFS/px4fmu_common/init.d-posix/px4-rc.jmavsim- SITL init scriptROMFS/px4fmu_common/init.d-posix/airframes/10017_jmavsim_iris- Airframe
SIH:
src/modules/simulation/simulator_sih/sih.cpp- Main implementationsrc/modules/simulation/simulator_sih/sih.hpp- Class definitionsrc/modules/simulation/simulator_sih/aero.hpp- Aerodynamic modelssrc/modules/simulation/simulator_sih/sih_params.c- Parameterssrc/modules/simulation/simulator_sih/Kconfig- Config symbolROMFS/px4fmu_common/init.d-posix/px4-rc.sihsim- SITL init scriptROMFS/px4fmu_common/init.d-posix/airframes/1004[0-5]_sihsim_*- SITL airframesROMFS/px4fmu_common/init.d/airframes/110[0-4]_*_sih.hil- Hardware airframes
Init scripts:
ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator- SITL simulator dispatcherROMFS/px4fmu_common/init.d/rcS- Hardware main startup (SYS_HITL logic at line 324)
Board configs:
boards/px4/sitl/default.px4board- Default SITL (includes Gazebo)boards/px4/sitl/sih.px4board- SIH-only SITL (no Gazebo dependencies)
The none cmake target (platforms/posix/CMakeLists.txt line 149) launches PX4 with no PX4_SYS_AUTOSTART override. It uses whatever SYS_AUTOSTART value is saved in parameters.bson from a previous run.
If a previous run used jmavsim_iris (autostart 10017), then make px4_sitl_sih none will auto-launch jMAVSim from the init scripts because the saved param matches the jMAVSim condition in px4-rc.simulator.
Fix: Use none_iris (explicitly sets autostart 10016) or delete stale params:
rm build/px4_sitl_sih/rootfs/parameters.bson build/px4_sitl_sih/rootfs/parameters_backup.bson