MAVLINKHUD

Overview

The SIM parameter group configures the Software-In-The-Loop (SITL) simulator environment. These parameters allow developers to simulate hardware failures, environmental conditions (wind/tides), and sensor noise without risking a physical vehicle.

Note: These parameters only exist when running the SITL binary; they are not present in physical flight controller hardware.

Key Concepts

1. Sensor Failures (SIM_..._FAIL)

Developers can simulate a sensor "dying" in mid-air to test failsafe logic.

  • SIM_GPS_DISABLE: Turns off GPS signal.
  • SIM_ACCEL_FAIL: Simulates an accelerometer failure.

2. Environmental Conditions

  • SIM_WIND_SPD / DIR: Injects constant wind.
  • SIM_WIND_TURB: Adds turbulence to the wind model.
  • SIM_WAVE_AMP: (Rover/Boat) Simulates water waves affecting the hull.

3. Sensor Noise and Bias

Allows for adding realistic imperfections to the simulated sensors to test EKF resilience.

  • SIM_GYR_RND: Random noise on the gyros.
  • SIM_MAG_ALY: Simulated magnetic anomaly.

Parameter Breakdown

  • SIM_SPEEDUP: Multiplier for simulation speed (e.g., 5.0 runs the sim at 5x real-time).
  • SIM_RATE_HZ: Update frequency of the physics engine.
  • SIM_VICON_...: Configures simulated Motion Capture (Vicon/Optitrack) indoor positioning.

Integration Guide

  • Safety Testing: Use SIM_GPS_JAM = 1 while in an autonomous mission to verify the vehicle correctly switches to non-GPS modes or triggers RTL.

Developer Notes

  • Library: libraries/SITL.
  • Frontends: SITL can be viewed in 3D using Gazebo, AirSim, or RealFlight.

SIM_ACC1_BIAS

$m/s^2$
Default 0
Range -10 10

Simulation Accelerometer 1 Bias (SIM_ACC1_BIAS)

Description

SIM_ACC1_BIAS allows you to test how ArduPilot handles a "Drifty" sensor.

Real accelerometers always have a slight offset (e.g. they might report 0.1 $m/s^2$ even when sitting perfectly level). ArduPilot calibrates this out during the "Accel Cal" process. By setting this parameter in SITL, you can intentionally introduce an error to verify that your calibration process or the EKF can handle it.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 0.5. If you haven't performed an Accel Cal in the simulation, the drone will think it is tilted and try to roll away.

SIM_ACC1_RND

m/s^2
Default 0
Range 0 10.0

Simulated Accelerometer 1 Noise (SIM_ACC1_RND)

Description

SIM_ACC1_RND allows you to test the robustness of the autopilot's navigation filters (EKF) by injecting artificial noise into the first simulated accelerometer.

In a real drone, motors and propellers create significant vibration. By increasing this parameter in SITL, you can see how much "shaking" your drone can tolerate before it loses its position estimate or becomes unstable.

The Engineer's View

Defined in SITL.cpp.
The simulation physics engine calculates the "True" acceleration of the vehicle. This parameter sets the standard deviation ($\sigma$) of a Gaussian distribution that is added to each sample:
$$ Accel\_{read} = Accel\_{true} + \mathcal{N}(0, \text{SIM\_ACC1\_RND}) $$

Tuning & Behavior

  • Default Value: 0 (Perfect, noise-free sensor).
  • Recommendation: Set to 0.5 or 1.0 to simulate a typical frame with some vibration. Set to 5.0+ to simulate a "Worst-case" high-vibration scenario.

SIM_ACC1_SCAL

Default 0
Range -0.1 0.1

Simulation Accelerometer 1 Scale (SIM_ACC1_SCAL)

Description

SIM_ACC1_SCAL simulates a "Sensitivity Error."

If an accelerometer is perfectly calibrated, it should report exactly 9.81 $m/s^2$ when facing down. A scale error means it might report 9.90 or 9.70 instead.

  • 0 (Default): Perfect scale.
  • 0.05: 5% scale error.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Use to verify the effectiveness of the 6-point Accel Calibration routine.

SIM_ACC2_BIAS

$m/s^2$
Default 0
Range -10 10

Simulation Accelerometer 2 Bias (SIM_ACC2_BIAS)

Description

SIM_ACC2_BIAS simulates drift on the secondary accelerometer.

See SIM_ACC1_BIAS for details.

SIM_ACC2_RND

null
Default 0
Range null

Accel 2 motor noise factor

Note: This parameter functions identically to SIM_ACC1_RND.

SIM_ACC2_SCAL

Default 0
Range -0.1 0.1

Simulation Accelerometer 2 Scale (SIM_ACC2_SCAL)

Description

SIM_ACC2_SCAL simulates sensitivity errors on the secondary accelerometer.

See SIM_ACC1_SCAL for details.

SIM_ACC3_BIAS

$m/s^2$
Default 0
Range -10 10

Simulation Accelerometer 3 Bias (SIM_ACC3_BIAS)

Description

SIM_ACC3_BIAS simulates drift on the tertiary IMU.

See SIM_ACC1_BIAS for details.

SIM_ACC3_RND

null
Default 0
Range null

Accel 3 motor noise factor

Note: This parameter functions identically to SIM_ACC1_RND.

SIM_ACC3_SCAL

Default 0
Range null

Accel 3 scaling factor

Note: This parameter configures instance 3. It functions identically to SIM_ACC1_SCAL.

SIM_ACC4_BIAS

Default 0
Range null

Accel 4 bias

Note: This parameter configures instance 4. It functions identically to SIM_ACC1_BIAS.

SIM_ACC4_RND

null
Default 0
Range null

Accel 4 motor noise factor

Note: This parameter functions identically to SIM_ACC1_RND.

SIM_ACC4_SCAL

Default 0
Range null

Accel 4 scaling factor

Note: This parameter configures instance 4. It functions identically to SIM_ACC1_SCAL.

SIM_ACC5_BIAS

Default 0
Range null

Accel 5 bias

Note: This parameter configures instance 5. It functions identically to SIM_ACC1_BIAS.

SIM_ACC5_RND

null
Default 0
Range null

Accel 5 motor noise factor

Note: This parameter functions identically to SIM_ACC1_RND.

SIM_ACC5_SCAL

Default 0
Range null

Accel 4 scaling factor

Note: This parameter configures instance 5. It functions identically to SIM_ACC1_SCAL.

SIM_ACCEL1_FAIL

Default 0
Range 0 1

Simulated Accelerometer 1 Failure (SIM_ACCEL1_FAIL)

Description

SIM_ACCEL1_FAIL allows you to simulate a catastrophic hardware failure of your primary accelerometer.

When set to 1, the sensor stops providing data. This is used by developers to verify that the "Lane Switching" logic in EKF3 correctly identifies the dead sensor and automatically switches the drone's control to Accelerometer 2 or 3 without crashing.

The Engineer's View

When this flag is set, the SITL backend for the IMU returns false on its read() calls or provides static/zero data. This triggers the EKF health monitoring system to mark the lane as unhealthy.

Tuning & Behavior

  • Default Value: 0 (Sensor working normally).
  • Recommendation: Only set to 1 while in flight in a safe simulation to verify your drone's redundant systems are working as expected.

SIM_ACCEL2_FAIL

null
Default 0
Range null

ACCEL2 Failure

Note: This parameter functions identically to SIM_ACCEL1_FAIL.

SIM_ACCEL3_FAIL

null
Default 0
Range null

ACCEL3 Failure

Note: This parameter functions identically to SIM_ACCEL1_FAIL.

SIM_ACCEL4_FAIL

null
Default 0
Range null

ACCEL4 Failure

Note: This parameter functions identically to SIM_ACCEL1_FAIL.

SIM_ACCEL5_FAIL

null
Default 0
Range null

ACCEL5 Failure

Note: This parameter functions identically to SIM_ACCEL1_FAIL.

SIM_ACC_FAIL_MSK

Default 0
Range 0 7

Simulated Accelerometer Failure Mask (SIM_ACC_FAIL_MSK)

Description

SIM_ACC_FAIL_MSK allows you to "kill" specific accelerometers in the simulator.

ArduPilot typically runs 3 IMUs (Inertial Measurement Units). By disabling one or two, you can verify that the EKF (Extended Kalman Filter) correctly switches to the remaining healthy sensors.

  • Bit 0 (1): Fail Accel 1
  • Bit 1 (2): Fail Accel 2
  • Bit 2 (4): Fail Accel 3

Tuning & Behavior

  • Default Value: 0 (All sensors active).
  • Testing: Set to 1 to kill Accel 1. Watch the EKF3.Lane messages in the GCS console to see the switch occur.

SIM_ACC_FILE_RW

Default 0
Range 0 3

Simulated Accelerometer File Read/Write (SIM_ACC_FILE_RW)

Description

SIM_ACC_FILE_RW allows you to "record" the vibration and movement of a real flight and "replay" it in the simulator.

This is an incredibly powerful tool for tuning filters. You can fly your real drone, capture the raw accelerometer noise, and then feed that exact noise into the simulator to test if your notch filters or EKF settings can handle it.

  • 0: Disabled (Standard simulation).
  • 1: Read data from file (Replay).
  • 2: Write data to file (Record).

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Use 2 during a short hover to capture a noise profile, then 1 to replay it while tuning INS_HNTCH_FREQ.

SIM_ACC_TRIM

deg
Default 0
Range -5 5

Simulation Accelerometer Trim (SIM_ACC_TRIM)

Description

SIM_ACC_TRIM simulates a drone where the flight controller isn't mounted perfectly level.

It injects a constant tilt into the accelerometer data. This is used to test how robust the EKF and flight controllers are to slight misalignments and to verify that "Accel Calibration" or "AHRS Trim" procedures work correctly in SITL.

SIM_ADSB_ALT

m
Default 1000
Range 0 10000

Simulated ADSB Altitude (SIM_ADSB_ALT)

Description

SIM_ADSB_ALT sets the cruising altitude for the fake traffic generated by SIM_ADSB_COUNT.

Tuning & Behavior

  • Default Value: 1000 m.
  • Testing: Set this to your flying altitude (e.g., 50m) to force "Near Miss" events.

SIM_ADSB_COUNT

Default -1
Range -1 100

Simulated ADSB Aircraft Count (SIM_ADSB_COUNT)

Description

SIM_ADSB_COUNT populates the sky with fake airplanes.

This allows you to test the "ADSB Avoidance" logic (AVOID_ADSB) without needing a real ADSB receiver or real planes flying nearby.

  • -1: Disabled.
  • 0: Enabled but 0 planes.
  • 1+: Generates X random aircraft flying near your home location.

Tuning & Behavior

  • Default Value: -1 (Disabled).
  • Testing: Set to 5 to see random traffic on your GCS map. Fly towards them to verify your drone triggers a failsafe or avoidance maneuver.

SIM_ADSB_RADIUS

m
Default 10000
Range 1000 100000

Simulated ADSB Radius (SIM_ADSB_RADIUS)

Description

SIM_ADSB_RADIUS sets the size of the "arena" for the simulated air traffic.

Simulated planes will spawn and fly within this distance from your home point.

Tuning & Behavior

  • Default Value: 10000 m (10 km).
  • Recommendation: Lower this to 1000 or 2000 if you want the traffic to be denser and closer to your drone for easier testing.

SIM_ADSB_TX

Default 0
Range 0 1

Simulated ADSB Transmission (SIM_ADSB_TX)

Description

SIM_ADSB_TX simulates the presence of an ADSB "Out" unit on your drone.

When enabled, the simulator will act as if it is broadcasting your position to the world. This is primarily for checking that the ADSB_RF_SELECT and other transponder settings are configured correctly in the GCS.

Tuning & Behavior

  • Default Value: 0 (Disabled).
  • 1: Enabled.

SIM_ADSB_TYPES

Default 0
Range 0 4294967295

Simulated ADSB Emitter Types (SIM_ADSB_TYPES)

Description

SIM_ADSB_TYPES filters the kind of "Fake Planes" the simulator generates.

If you only want to test how your drone reacts to other drones (UAVs), you can disable the "747 Jumbo Jet" simulation.

  • Bit 0: Light (Cessna)
  • Bit 1: Small (Learjet)
  • Bit 2: Large (747)
  • Bit 14: UAV

Tuning & Behavior

  • Default Value: 0 (All types).
  • Recommendation: Leave at 0 to test against a realistic mix of air traffic.

SIM_AIS_RADIUS

m
Default 0
Range 0 100000

Simulation AIS Radius (SIM_AIS_RADIUS)

Description

SIM_AIS_RADIUS enables the simulation of other ships for maritime operations.

When set to a positive value, ArduPilot will generate "Fake" ships (AIS targets) within this distance. This allows you to test obstacle avoidance and traffic monitoring systems on boats and autonomous ships.

SIM_ARSPD2_FAIL

null
Default 0
Range null

Airspeed sensor failure

Note: This parameter functions identically to SIM_ARSPD_FAIL.

SIM_ARSPD2_FAILP

Pa
Default 0
Range null

Airspeed sensor failure pressure

Note: This parameter functions identically to SIM_ARSPD_FAILP.

SIM_ARSPD2_OFS

mGauss
Default 0
Range -400 400

Compass offsets in milligauss on the Z axis

Note: This parameter functions identically to SIM_ARSPD_OFS.

SIM_ARSPD2_PITOT

Pa
Default 0
Range null

Airspeed pitot tube failure pressure

Note: This parameter functions identically to SIM_ARSPD_PITOT.

SIM_ARSPD2_RATIO

null
Default 2
Range null

Airspeed ratio

Note: This parameter functions identically to SIM_ARSPD_RATIO.

SIM_ARSPD2_RND

null
Default 2.0
Range null

None

Note: This parameter functions identically to SIM_ARSPD_RND.

SIM_ARSPD2_SIGN

null
Default 0
Range null

Airspeed signflip

Note: This parameter functions identically to SIM_ARSPD_SIGN.

SIM_ARSPD_FAIL

m/s
Default 0
Range 0 100

Simulated Airspeed Failure Value (SIM_ARSPD_FAIL)

Description

SIM_ARSPD_FAIL allows you to simulate a "Stuck Sensor" or a "Clogged Pitot Tube."

By setting this to a static value (like 0 or 100), you can verify that the autopilot detects the failure and switches to "Synthetic Airspeed" (estimating speed from throttle and pitch) or triggers a failsafe.

The Engineer's View

If this value is non-zero (or if you toggle the failure flag in the SITL backend), the sensor driver will lock its output to this value.

  • 0 m/s: Simulates a pitot tube cover left on.
  • High Value: Simulates a sensor blowing out or water ingress.

Tuning & Behavior

  • Default Value: 0 (Disabled/Normal Operation).
  • Testing: Set to 0 while flying to simulate a blockage. Watch if the EKF declares the sensor "Unhealthy."

SIM_ARSPD_FAILP

Pa
Default 0
Range 0 1000

Simulated Airspeed Failure Pressure (SIM_ARSPD_FAILP)

Description

SIM_ARSPD_FAILP allows you to choose what "Broken" looks like for your Pitot tube.

If SIM_ARSPD_FAIL is active, the sensor will freeze at this pressure.

  • 0 Pa: Simulates a clogged tube (Zero airspeed). Useful for testing stall warnings.
  • High Value: Simulates a blocked static port (High airspeed).

Tuning & Behavior

  • Default Value: 0 Pa.

SIM_ARSPD_OFS

Pa
Default 0
Range 0 100

Simulated Airspeed Offset (SIM_ARSPD_OFS)

Description

SIM_ARSPD_OFS simulates a calibration error.

Airspeed sensors measure minute pressure differences. If the sensor isn't zeroed correctly before flight (e.g., if it was windy when you plugged in the battery), it will report speed even when sitting still. This parameter allows you to simulate that error and test if your pre-flight checks catch it.

Tuning & Behavior

  • Default Value: 0 Pa.
  • Testing: Set to 100. You should see the HUD report an airspeed of 5-10 m/s even while the drone is on the ground.

SIM_ARSPD_PITOT

Pa
Default 0
Range 0 1000

Simulated Pitot Blockage Pressure (SIM_ARSPD_PITOT)

Description

SIM_ARSPD_PITOT simulates a blocked pitot tube (e.g., mud wasp nest).

If you set SIM_ARSPD_FAIL to enable failure, this is the pressure value the sensor will output.

Tuning & Behavior

  • Default Value: 0 Pa.

SIM_ARSPD_RATIO

Default 2
Range 1 4

Simulated Airspeed Ratio (SIM_ARSPD_RATIO)

Description

SIM_ARSPD_RATIO sets the sensitivity of the virtual pitot tube.

This corresponds to the ARSPD_RATIO parameter in the flight controller. If they don't match, your airspeed reading will be wrong.

Tuning & Behavior

  • Default Value: 2.
  • Testing: Change this to 3 and see if ARSPD_AUTOCAL can figure it out.

SIM_ARSPD_RND

m/s
Default 2
Range 0 20

Simulated Airspeed Noise (SIM_ARSPD_RND)

Description

SIM_ARSPD_RND injects noise into the virtual pitot tube.

Airspeed sensors are notoriously noisy due to wind gusts and turbulence. This parameter helps you tune your TECS (Total Energy Control System) to ignore that noise.

  • 0: Perfect, clean airspeed data.
  • 2 (Default): Realistic turbulence.

Tuning & Behavior

  • Default Value: 2.0 m/s.
  • Recommendation: Keep at 2.0 to ensure your PID tuning is robust enough for real-world flight.

SIM_ARSPD_SIGN

Default 1
Range -1 1

Simulated Airspeed Sign (SIM_ARSPD_SIGN)

Description

SIM_ARSPD_SIGN simulates a common plumbing error: swapping the Pitot and Static tubes.

If set to -1, the airspeed sensor will report negative pressure, which typically results in zero airspeed or an error message.

Tuning & Behavior

  • Default Value: 1.

SIM_BAR2_DELAY

s
Default AR_PIVOT_DELAY_DEFAULT
Range 0 60

Pivot Delay

Note: This parameter functions identically to SIM_BARO_DELAY.

SIM_BAR2_DISABLE

null
Default 0
Range null

Barometer disable

Note: This parameter functions identically to SIM_BARO_DISABLE.

SIM_BAR2_DRIFT

m/s
Default 0
Range null

Barometer altitude drift

Note: This parameter functions identically to SIM_BARO_DRIFT.

SIM_BAR2_FREEZE

null
Default 0
Range null

Barometer freeze

Note: This parameter functions identically to SIM_BARO_FREEZE.

SIM_BAR2_GLITCH

m
Default 0
Range null

Barometer glitch

Note: This parameter functions identically to SIM_BARO_GLITCH.

SIM_BAR2_RND

null
Default 2.0
Range null

None

Note: This parameter functions identically to SIM_BARO_RND.

SIM_BAR2_WCF_BAK

null
Default 0.0
Range null

Wind coefficient backward

Note: This parameter functions identically to SIM_BARO_WCF_BAK.

SIM_BAR2_WCF_DN

null
Default 0.0
Range -1.0 1.0

Pressure error coefficient in negative Z direction (down)

Note: This parameter functions identically to SIM_BARO_WCF_DN.

SIM_BAR2_WCF_FWD

null
Default 0.0
Range -1.0 1.0

Pressure error coefficient in positive X direction (forward)

Note: This parameter functions identically to SIM_BARO_WCF_FWD.

SIM_BAR2_WCF_LFT

null
Default 0.0
Range -1.0 1.0

Pressure error coefficient in negative Y direction (left)

Note: This parameter functions identically to SIM_BARO_WCF_LFT.

SIM_BAR2_WCF_RGT

null
Default 0.0
Range -1.0 1.0

Pressure error coefficient in positive Y direction (right)

Note: This parameter functions identically to SIM_BARO_WCF_RGT.

SIM_BAR2_WCF_UP

null
Default 0.0
Range -1.0 1.0

Pressure error coefficient in positive Z direction (up)

Note: This parameter functions identically to SIM_BARO_WCF_UP.

SIM_BAR3_DELAY

s
Default AR_PIVOT_DELAY_DEFAULT
Range 0 60

Pivot Delay

Note: This parameter functions identically to SIM_BARO_DELAY.

SIM_BAR3_DISABLE

null
Default 0
Range null

Barometer disable

Note: This parameter functions identically to SIM_BARO_DISABLE.

SIM_BAR3_DRIFT

m/s
Default 0
Range null

Barometer altitude drift

Note: This parameter functions identically to SIM_BARO_DRIFT.

SIM_BAR3_FREEZE

null
Default 0
Range null

Barometer freeze

Note: This parameter functions identically to SIM_BARO_FREEZE.

SIM_BAR3_GLITCH

m
Default 0
Range null

Barometer glitch

Note: This parameter functions identically to SIM_BARO_GLITCH.

SIM_BAR3_RND

null
Default 2.0
Range null

None

Note: This parameter functions identically to SIM_BARO_RND.

SIM_BAR3_WCF_BAK

null
Default 0.0
Range null

Wind coefficient backward

Note: This parameter functions identically to SIM_BARO_WCF_BAK.

SIM_BAR3_WCF_DN

null
Default 0.0
Range -1.0 1.0

Pressure error coefficient in negative Z direction (down)

Note: This parameter functions identically to SIM_BARO_WCF_DN.

SIM_BAR3_WCF_FWD

null
Default 0.0
Range -1.0 1.0

Pressure error coefficient in positive X direction (forward)

Note: This parameter functions identically to SIM_BARO_WCF_FWD.

SIM_BAR3_WCF_LFT

null
Default 0.0
Range -1.0 1.0

Pressure error coefficient in negative Y direction (left)

Note: This parameter functions identically to SIM_BARO_WCF_LFT.

SIM_BAR3_WCF_RGT

null
Default 0.0
Range -1.0 1.0

Pressure error coefficient in positive Y direction (right)

Note: This parameter functions identically to SIM_BARO_WCF_RGT.

SIM_BAR3_WCF_UP

null
Default 0.0
Range -1.0 1.0

Pressure error coefficient in positive Z direction (up)

Note: This parameter functions identically to SIM_BARO_WCF_UP.

SIM_BARO_COUNT

Default 1
Range 1 3

Simulated Barometer Count (SIM_BARO_COUNT)

Description

SIM_BARO_COUNT defines how many virtual atmospheric pressure sensors are available to the autopilot.

By increasing this to 2 or 3, you can test ArduPilot's multi-baro redundancy and health monitoring. You can then use other SIM_BARx_... parameters to fail one sensor and watch the EKF switch to the backup.

Tuning & Behavior

  • Default Value: 1.
  • Recommendation: Set to 2 for a realistic simulation of standard flight controller hardware (which often has two baros).
  • Reboot Required: Yes.

SIM_BARO_DELAY

ms
Default 0
Range 0 1000

Simulated Barometer Delay (SIM_BARO_DELAY)

Description

SIM_BARO_DELAY adds lag to the altitude reading. High lag can cause the drone to "bounce" in AltHold because the controller is reacting to where the drone was, not where it is.

Tuning & Behavior

  • Default Value: 0
  • Recommendation: Use to test controller stability.

SIM_BARO_DISABLE

Default 0
Range 0 1

Disable Simulated Barometer (SIM_BARO_DISABLE)

Description

SIM_BARO_DISABLE kills the primary barometer signal.

Use this to test your drone's ability to maintain altitude using ONLY the IMU (which will drift) or a secondary source (like a Rangefinder).

Tuning & Behavior

  • Default Value: 0
  • Recommendation: Use in flight to verify your "Secondary Altitude Source" logic.

SIM_BARO_DRIFT

m/s
Default 0
Range 0 1.0

Simulated Barometer Drift (SIM_BARO_DRIFT)

Description

SIM_BARO_DRIFT simulates a barometer that is slowly losing calibration or being affected by changing weather pressure.

Real barometers drift as the weather changes (e.g., a storm front moving in). This parameter adds a constant vertical velocity error to the sensor.

Tuning & Behavior

  • Default Value: 0 m/s.
  • Recommendation: Set to 0.1 m/s to test if the EKF can use GPS vertical velocity to correct the baro drift.

SIM_BARO_FREEZE

Default 0
Range 0 1

Simulated Barometer Freeze (SIM_BARO_FREEZE)

Description

SIM_BARO_FREEZE locks the barometer value.

This simulates a sensor driver crash or a clogged static port. If the drone climbs or descends, the barometer will report 0 vertical speed.

Tuning & Behavior

  • Default Value: 0 (Disabled).
  • 1: Freeze enabled.

SIM_BARO_GLITCH

m
Default 0
Range 0 100

Simulated Barometer Glitch (SIM_BARO_GLITCH)

Description

SIM_BARO_GLITCH applies an instant step-change to the altitude reading.

This simulates events like opening a window in a pressurized room or a sudden pressure wave from a passing truck.

Tuning & Behavior

  • Default Value: 0 m.
  • Testing: Set to 50 (meters) while hovering. Verify that the drone does NOT shoot up/down 50 meters instantly. The EKF should reject the jump or smooth it out.

SIM_BARO_RND

Pa
Default 0.2
Range 0 10.0

Simulated Barometer Noise (SIM_BARO_RND)

Description

SIM_BARO_RND simulates atmospheric pressure noise. Since ArduPilot uses the barometer for altitude, this noise directly affects how "bouncy" the altitude hold is in flight.

The Engineer's View

Adds Gaussian noise to the simulated pressure reading. Because 1 Pascal is roughly 8cm of altitude at sea level, a noise value of 0.2 represents about 1.6cm of altitude jitter.

Tuning & Behavior

  • Default Value: 0.2 Pa
  • Effect of Increasing: The drone will struggle to maintain a precise altitude, and the climb rate estimate will become noisier.

SIM_BARO_WCF_BAK

Default 0
Range -0.1 0.1

Simulation Barometer Wind Coefficient Backward (SIM_BARO_WCF_BAK)

Description

SIM_BARO_WCF_BAK simulates pressure errors when the drone is flying backwards.

See SIM_BARO_WCF_FWD for more details.

SIM_BARO_WCF_DN

Default 0
Range -1.0 1.0

Simulation Baro Wind Coeff (SIM_BARO_WCF_DN)

Description

SIM_BARO_WCF_DN simulates aerodynamic interference that makes the altitude reading glitch during a fast descent.

See BARO1_WCF_ENABLE for details on the real-world compensation model. This parameter allows you to inject those same errors into SITL to test your compensation tuning.

SIM_BARO_WCF_FWD

Default 0
Range -0.1 0.1

Simulation Barometer Wind Coefficient Forward (SIM_BARO_WCF_FWD)

Description

SIM_BARO_WCF_FWD simulates "Static Port Error."

On real planes, as the airspeed increases, the pressure around the fuselage drops (Bernoulli's principle). If your barometer isn't perfectly vented, this can cause the drone to think it is climbing when it is actually just speeding up. This parameter allows you to simulate that effect to test compensation algorithms (BARO_WCF_ENABLE).

The Mathematics

The pressure error ($\Delta P$) is calculated as:
$$ \Delta P = \text{WCF} \cdot \frac{1}{2} \cdot \rho \cdot V^2 $$

Where:

  • $V$ is airspeed in the forward direction.
  • $\rho$ is air density.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 0.02. Fly the drone fast in a straight line. If you see the reported altitude change while you are at a constant height, the simulation is working.

SIM_BARO_WCF_LFT

Pa/(m/s)^2
Default 0
Range -10 10

Simulated Baro Wind Comp Factor Left (SIM_BARO_WCF_LFT)

Description

Defines pressure change due to wind from the left. See SIM_BARO_WCF_UP.

SIM_BARO_WCF_RGT

Pa/(m/s)^2
Default 0
Range -10 10

Simulated Baro Wind Comp Factor Right (SIM_BARO_WCF_RGT)

Description

Defines pressure change due to wind from the right. See SIM_BARO_WCF_UP.

SIM_BARO_WCF_UP

Pa/(m/s)^2
Default 0
Range -10 10

Simulated Baro Wind Comp Factor Up (SIM_BARO_WCF_UP)

Description

SIM_BARO_WCF_UP simulates the "Bernoulli Effect" on your static port.

When wind blows across a hole (static port), it creates a pressure drop (or rise), causing the drone to think it is at a different altitude. This parameter defines how much the reported pressure changes when wind hits the drone from the top.

The Mathematics

$$ \Delta P = C\_{up} \times V\_{up}^2 $$

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Use -0.05 to simulate a typical drone where propwash creates a low-pressure zone above the flight controller.

SIM_BATT_CAPACITY

mAh
Default 10000
Range 0 50000

Simulation Battery Capacity (SIM_BATT_CAPACITY)

Description

SIM_BATT_CAPACITY defines the size of the virtual fuel tank.

SITL calculates current draw based on motor thrust. This parameter allows you to test battery failsafe logic by simulating a realistic discharge curve.

Tuning & Behavior

  • Default Value: 10000 mAh.
  • Testing: Set to a small value (e.g. 500) to quickly trigger a "Low Battery" failsafe during a test flight.

SIM_BATT_CAP_AH

Ah
Default 0
Range 0 1000

Simulated Battery Capacity (SIM_BATT_CAP_AH)

Description

SIM_BATT_CAP_AH defines how much "Fuel" the virtual battery has.

As you fly in SITL, the autopilot calculates current draw based on motor throttle. This parameter determines how fast the voltage drops. If set to 0, the battery is "Infinite" and will never drain.

SIM_BATT_VOLTAGE

V
Default 12.6
Range 0 100

Simulation Battery Voltage (SIM_BATT_VOLTAGE)

Description

SIM_BATT_VOLTAGE sets the initial charge state.

Tuning & Behavior

  • Default Value: 12.6 V (3S Lipo).
  • Testing: Set to 10.5 to test Battery Failsafe trigger on boot or takeoff.

SIM_BAUDLIMIT_EN

Default 0
Range 0 1

Simulated Baud Rate Limiting Enable (SIM_BAUDLIMIT_EN)

Description

SIM_BAUDLIMIT_EN forces the simulator to respect the physics of serial data transfer speeds.

By default, SITL sends data as fast as the CPU allows. If you enable this, a simulated 57600 baud link will actually choke if you try to send too much data, causing packet loss and latency.

Tuning & Behavior

  • Default Value: 0 (Unlimited speed).
  • Recommendation: Enable this when testing telemetry radios or low-bandwidth links to verify your stream rates (SRx_params) are configured correctly.

SIM_BUOYANCY

N
Default 1
Range -100 100

Simulation Buoyancy (SIM_BUOYANCY)

Description

SIM_BUOYANCY defines how much the simulated submarine wants to float or sink.

  • Positive Value: Net upwards force (Positive buoyancy). The sub floats to the surface.
  • Negative Value: Net downwards force (Negative buoyancy). The sub sinks to the bottom.
  • 0: Neutral buoyancy. The sub stays at its current depth (Ideal for ROVs).

Tuning & Behavior

  • Testing: Essential for tuning the vertical depth controller on ArduSub.

SIM_BZ_ENABLE

Default 0
Range 0 1

Simulation Buzzer Enable (SIM_BZ_ENABLE)

Description

SIM_BZ_ENABLE activates a virtual beeper.

When enabled, SITL will log and potentially play sound for arming beeps, failsafe warnings, and other audio cues produced by the autopilot. Useful for debugging new melody patterns or verifying failsafe alerts.

SIM_BZ_PIN

Default -1
Range -1 100

Simulation Buzzer Pin (SIM_BZ_PIN)

Description

SIM_BZ_PIN tells the simulator which virtual pin is connected to the beeper.

SIM_CAN_SRV_MSK

Default 0
Range 0 4294967295

Simulated CAN Servo Mask (SIM_CAN_SRV_MSK)

Description

SIM_CAN_SRV_MSK tells the simulator which motors or servos are "Digital" (CAN).

Normally, SITL simulates servos as direct wires. If you are developing or testing DroneCAN hardware (using AP_Periph), you can set this mask. Any bit set to 1 will cause the simulator to expect that channel's data to come from a virtual CAN node rather than the main flight controller's internal logic.

Tuning & Behavior

  • 0: All servos simulated as direct internal connections.
  • Bit 0 (1): Servo 1 is a CAN servo.
  • Bit 3 (8): Servo 4 is a CAN servo.

SIM_CAN_TYPE1

Default 1
Range 0 2

Simulated CAN 1 Transport Type (SIM_CAN_TYPE1)

Description

SIM_CAN_TYPE1 tells the simulator how to send "CAN Messages" between SITL and other simulated devices (like a DroneCAN GPS).

  • 0: None.
  • 1: MulticastUDP (Default). Sends messages over your computer's local network. This is the standard way SITL talks to the "CANDevices" or "UAVCAN GUI Tool."
  • 2: SocketCAN. Uses the Linux kernel's native CAN bus driver (Linux only).

Tuning & Behavior

  • Default Value: 1.
  • Recommendation: Leave at 1 for all standard DroneCAN testing.

SIM_CAN_TYPE2

null
Default uint8_t(CANTransport::MulticastUDP
Range null

transport type for second CAN interface

Note: This parameter functions identically to SIM_CAN_TYPE1.

SIM_CLAMP_CH

Default 0
Range 0 16

Simulated Clamp Channel (SIM_CLAMP_CH)

Description

SIM_CLAMP_CH creates a virtual "Mag-Lock" on the landing gear.

When the selected RC channel is High (PWM > 1800), the drone is physically stuck to the ground, regardless of throttle. This is useful for testing "Ground Idle" vibration or tuning PID loops without the drone taking off.

Tuning & Behavior

  • 0: Disabled.
  • 1-16: RC Channel number.

SIM_DRIFT_SPEED

m/s
Default 0.05
Range 0 0.5

Simulation GPS Drift Speed (SIM_DRIFT_SPEED)

Description

SIM_DRIFT_SPEED simulates the "Wandering" effect of GPS.

Real GPS position is never perfectly still; it slowly drifts around a central point due to atmospheric changes. This parameter controls how fast that drift moves.

Tuning & Behavior

  • Default Value: 0.05 m/s.
  • Testing: Increase to 0.2 to test if your Loiter PID tuning is tight enough to hold position against a "moving" GPS target.

SIM_DRIFT_TIME

s
Default 5
Range 1 50

Simulation GPS Drift Time (SIM_DRIFT_TIME)

Description

SIM_DRIFT_TIME controls how often the GPS drift changes direction.

See SIM_DRIFT_SPEED.

SIM_EFI_TYPE

Default 0
Range 0 8

Simulated EFI Type (SIM_EFI_TYPE)

Description

SIM_EFI_TYPE adds a virtual engine to the simulation.

  • 0: Disabled.
  • 1: MegaSquirt.
  • 2: Loweheiser.
  • 8: Hirth.

Tuning & Behavior

  • Default Value: 0.
  • Usage: Enable this to test your EFI_* parameter configuration and OSD layout.

SIM_ENGINE_FAIL

Default -1
Range -1 8

Simulated Engine Failure (SIM_ENGINE_FAIL)

Description

SIM_ENGINE_FAIL selects the victim motor for failure testing.

  • -1 (Default): No failure.
  • 0: Motor 1 fails.
  • 1: Motor 2 fails.

Tuning & Behavior

  • Default Value: -1.
  • Procedure:
    1. Take off and hover.
    2. Set SIM_ENGINE_MUL to 0.
    3. Set SIM_ENGINE_FAIL to 0 (Motor 1).
    4. Observe if the drone crashes or spins.

SIM_ENGINE_MUL

Default 1.0
Range 0 1.0

Simulation Engine Multiplier (SIM_ENGINE_MUL)

Description

SIM_ENGINE_MUL allows you to kill or weaken a motor in flight.

This is the primary tool for testing multirotor motor redundancy (e.g. Octocopter failure) or plane engine-out handling.

  • 1.0 (Default): Full power.
  • 0.0: Complete motor failure.
  • 0.5: 50% power loss (damaged prop or ESC).

Tuning & Behavior

  • Usage: You must also set SIM_ENGINE_FAIL to the motor number (0-indexed) you want to affect.

SIM_ESC_ARM_RPM

RPM
Default 0
Range 0 5000

Simulated ESC Armed RPM (SIM_ESC_ARM_RPM)

Description

SIM_ESC_ARM_RPM sets the "Idle Speed" for the virtual RPM feedback.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Set to 500 or 1000 to simulate the low-end spinning of motors while the drone is on the ground but armed.

SIM_ESC_TELEM

Default 0
Range 0 2

Simulated ESC Telemetry Type (SIM_ESC_TELEM)

Description

SIM_ESC_TELEM enables the virtual return path for motor data.

If you are testing DShot ESC Telemetry or RPM filtering, you need this enabled so the autopilot "sees" the RPM and voltage data coming back from the virtual ESCs.

  • 0: Disabled.
  • 1: Enabled (Standard RPM + Voltage).
  • 2: Bidirectional DShot (RPM only, but high-speed).

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Set to 1 to verify your OSD battery display and motor fail detection.

SIM_FLOAT_EXCEPT

Default 1
Range 0 1

Simulated Floating Point Exceptions (SIM_FLOAT_EXCEPT)

Description

SIM_FLOAT_EXCEPT is a developer safety tool.

If enabled, the simulator will immediately "Hard Crash" if any part of the code performs an illegal math operation (like dividing by zero or taking the square root of a negative number). This is vital for catching bugs before they are ever flown on real hardware.

Tuning & Behavior

  • Default Value: 1 (Enabled).
  • Recommendation: Keep at 1 at all times unless you are debugging a known math issue that you need the simulator to bypass.

SIM_FLOW_DELAY

ms
Default 0
Range 0 500

Simulated Optical Flow Delay (SIM_FLOW_DELAY)

Description

SIM_FLOW_DELAY simulates the processing lag of a smart camera (like HereFlow or PX4Flow).

Tuning & Behavior

  • Default Value: 0 ms.
  • Recommendation: Set to 20 to match real hardware.

SIM_FLOW_ENABLE

Default 0
Range 0 1

Simulated Optical Flow Enable (SIM_FLOW_ENABLE)

Description

SIM_FLOW_ENABLE adds a virtual Optical Flow camera to the drone.

This allows you to test non-GPS loiter modes (FlowHold) and indoor navigation logic.

Tuning & Behavior

  • Default Value: 0 (Disabled).
  • 1: Enabled.

SIM_FLOW_POS

m
Default 0
Range 0 5

Simulation Optical Flow Position (SIM_FLOW_POS)

Description

SIM_FLOW_POS defines where the optical flow sensor is mounted in the simulator.

Just like the IMU and GPS, if the optical flow sensor is away from the COG, it will experience extra movement during rotations. This parameter tests the flight controller's ability to use the FLOW_POS_X/Y/Z parameters to compensate for these "lever arm" effects.

SIM_FLOW_RATE

Hz
Default 10
Range 1 50

Simulated Optical Flow Rate (SIM_FLOW_RATE)

Description

SIM_FLOW_RATE sets the data frequency of the virtual flow sensor.

Tuning & Behavior

  • Default Value: 10 Hz.
  • Recommendation: Match your hardware specs (e.g., 50Hz for high-end sensors).

SIM_FLOW_RND

rad/s
Default 0.05
Range 0 0.5

Simulated Optical Flow Noise (SIM_FLOW_RND)

Description

SIM_FLOW_RND simulates the "jitter" of an optical flow sensor looking at a difficult surface (like grass or carpet).

Tuning & Behavior

  • Default Value: 0.05 $rad/s$.
  • Recommendation: Increase to 0.2 to test if your drone can hold position over low-contrast surfaces.

SIM_FTOWESC_ENA

Default 0
Range 0 1

Simulation FETtec OneWire ESC Enable (SIM_FTOWESC_ENA)

Description

SIM_FTOWESC_ENA activates the virtual FETtec OneWire interface.

This allows you to test the SERVO_FTW_MASK configuration and RPM telemetry feedback without having a physical FETtec ESC board connected.

SIM_FTOWESC_POW

W
Default 0
Range 0 10000

Simulated TOWESC Power (SIM_FTOWESC_POW)

Description

SIM_FTOWESC_POW defines the maximum power capacity of the heavy-lift motor simulation.

SIM_GLD_BLN_BRST

Default 0
Range 0 1

Simulation Balloon Burst (SIM_GLD_BLN_BRST)

Description

SIM_GLD_BLN_BRST triggers the "Release" phase of a balloon glider test.

For drones that are carried to high altitudes by balloons, this parameter allows you to simulate the moment the balloon pops or the drone is released, instantly transitioning the physics model from buoyant ascent to aerodynamic glide.

SIM_GLD_BLN_RATE

Hz
Default 0
Range 0 100

Simulated Glider/Balloon Rate (SIM_GLD_BLN_RATE)

Description

SIM_GLD_BLN_RATE sets the physics resolution for slow-moving airframes like gliders and weather balloons.

SIM_GND_BEHAV

Default -1
Range -1 2

Simulated Ground Behavior (SIM_GND_BEHAV)

Description

SIM_GND_BEHAV modifies how the drone interacts with the virtual earth.

  • -1: Automatic (standard).
  • 0: Non-Tailsitter (stays flat).
  • 1: Tailsitter (leans back onto its tail).
  • 2: Stay on ground (locked position).

Tuning & Behavior

  • Default Value: -1.
  • Recommendation: Leave at -1 unless you are testing a tailsitter QuadPlane.

SIM_GPS1_ALT_OFS

m
Default 0
Range -100 100

Simulated GPS 1 Altitude Offset (SIM_GPS1_ALT_OFS)

Description

SIM_GPS1_ALT_OFS adds a constant error to the GPS altitude.

This is used to verify that the EKF can handle a disagreement between the Barometer (which reports correct altitude) and the GPS (which reports offset altitude).

Tuning & Behavior

  • Default Value: 0 m.
  • Testing: Set to 20. The EKF should initially report a large height innovation (error), then slowly shift the GPS bias or reject the GPS.

SIM_GPS1_ENABLE

Default 1
Range 0 1

Simulated GPS 1 Enable (SIM_GPS1_ENABLE)

Description

SIM_GPS1_ENABLE is the power switch for the virtual GPS.

If you want to test how your drone flies with ONLY the secondary GPS, or no GPS at all, you can use this parameter to turn off the primary unit.

Tuning & Behavior

  • Default Value: 1 (Enabled).
  • 0: Disabled.

SIM_GPS1_HDG_OFS

deg
Default 0
Range 0 360

Simulated GPS 1 Heading Offset (SIM_GPS1_HDG_OFS)

Description

SIM_GPS1_HDG_OFS adds a constant error to the heading reported by the GPS.

This is only relevant if SIM_GPS_HDG is enabled (simulating a Dual Antenna GPS). It tests the EKF's ability to handle Compass/GPS yaw disagreement.

Tuning & Behavior

  • Default Value: 0 deg.
  • Testing: Set to 90. The EKF should trigger a "Yaw Alignment" error.

SIM_GPS1_TYPE

Default 1
Range 0 19

Simulated GPS 1 Type (SIM_GPS1_TYPE)

Description

SIM_GPS1_TYPE tells the simulator which GPS language to speak to the autopilot.

  • 1: UBlox (Default). The standard binary protocol used by M8N/F9P modules.
  • 5: NMEA. The standard text-based protocol used by older or generic GPS units.
  • 19: MSP. MultiWii Serial Protocol, used by DJI or Walksnail video systems to pass GPS data.

Tuning & Behavior

  • Default Value: 1.
  • Recommendation: Keep at 1 (UBlox) for the most realistic simulation of standard ArduPilot hardware.

SIM_GPS2_ACC

null
Default 0.3
Range null

GPS 2 Accuracy

Note: This parameter functions identically to SIM_GPS_ACC.

SIM_GPS2_ALT_OFS

mGauss
Default 0
Range -400 400

Compass offsets in milligauss on the Z axis

Note: This parameter configures instance 2. It functions identically to SIM_GPS_ALT_OFS.

SIM_GPS2_BYTELOS

%
Default 0
Range 0 100

Simulated GPS 2 Byte Loss (SIM_GPS2_BYTELOS)

Description

SIM_GPS2_BYTELOS degrades the connection to the secondary GPS.

By dropping random bytes, you can simulate a loose cable or electrical noise on the UART line. This tests the GPS driver's ability to re-sync and the EKF's ability to handle packet loss.

Tuning & Behavior

  • Default Value: 0%.

SIM_GPS2_DISABLE

Default 1
Range null

GPS 2 disable

Note: This parameter functions identically to SIM_GPS_DISABLE.

SIM_GPS2_DRFTALT

m/s
Default 0
Range 0 5

Simulated GPS 2 Altitude Drift (SIM_GPS2_DRFTALT)

Description

SIM_GPS2_DRFTALT makes the secondary GPS "Float" vertically.

GPS altitude is notoriously unreliable. This parameter adds a slow, continuous change to the reported height, allowing you to verify that the EKF (which usually trusts the Barometer for height) ignores the bad GPS altitude data.

Tuning & Behavior

  • Default Value: 0.

SIM_GPS2_ENABLE

null
Default 0
Range null

Enable pullup after altitude wait

Note: This parameter functions identically to SIM_GPS1_ENABLE.

SIM_GPS2_GLTCH

m
Default 0
Range -100 100

Simulation GPS 2 Glitch (SIM_GPS2_GLTCH)

Description

SIM_GPS2_GLTCH allows you to test dual-GPS configurations by "breaking" the secondary receiver.

By injecting a glitch into only one GPS, you can verify that the EKF successfully switches to the healthy receiver (if configured for GPS_AUTO_SWITCH = 1).

SIM_GPS2_HDG

deg
Default 0
Range 0 360

Simulated GPS 2 Heading (SIM_GPS2_HDG)

Description

SIM_GPS2_HDG sets the "True North" for the secondary GPS if it is a "Moving Baseline" unit.

By setting this to a value different from the actual vehicle heading, you can test how the autopilot handles "GPS Yaw" errors or alignment issues.

Tuning & Behavior

  • Default Value: 0 (Matches vehicle heading).

SIM_GPS2_HDG_OFS

mGauss
Default 0
Range -400 400

Compass offsets in milligauss on the Z axis

Note: This parameter functions identically to SIM_GPS1_HDG_OFS.

SIM_GPS2_HZ

Hz
Default 5
Range null

GPS 2 Hz

Note: This parameter functions identically to SIM_GPS_HZ.

SIM_GPS2_JAM

null
Default 0
Range null

GPS jamming enable

Note: This parameter configures instance 2. It functions identically to SIM_GPS_JAM.

SIM_GPS2_LAG_MS

ms
Default 100
Range null

GPS 2 Lag

Note: This parameter functions identically to SIM_GPS_LAG_MS.

SIM_GPS2_LCKTIME

s
Default 0
Range 0 120

Simulation GPS 2 Lock Time (SIM_GPS2_LCKTIME)

Description

SIM_GPS2_LCKTIME allows you to simulate a scenario where one GPS gets a fix much later than the other, testing the autopilot's primary/secondary switchover logic.

SIM_GPS2_NOISE

m
Default 0
Range 0 10

Simulated GPS 2 Noise (SIM_GPS2_NOISE)

Description

SIM_GPS2_NOISE adds jitter to the secondary GPS.

Use this to test GPS Blending (GPS_AUTO_SWITCH = 2). You can make GPS 2 noisier than GPS 1 and verify that the autopilot correctly weights GPS 1 higher.

Tuning & Behavior

  • Default Value: 0.

SIM_GPS2_NUMSATS

null
Default 10
Range null

GPS 2 Num Satellites

Note: This parameter functions identically to SIM_GPS_NUMSATS.

SIM_GPS2_POS

m
Default 0
Range null

GPS 2 Position

Note: This parameter functions identically to SIM_GPS_POS.

SIM_GPS2_TYPE

null
Default TILT_TYPE_CONTINUOUS
Range null

Tiltrotor type

Note: This parameter configures instance 2. It functions identically to SIM_GPS_TYPE.

SIM_GPS2_VERR

Default 0
Range null

GPS 2 Velocity Error

Note: This parameter configures instance 2. It functions identically to SIM_GPS_VERR.

SIM_GPS3_ALT_OFS

mGauss
Default 0
Range -400 400

Compass offsets in milligauss on the Z axis

Note: This parameter configures instance 3. It functions identically to SIM_GPS_ALT_OFS.

SIM_GPS3_ENABLE

null
Default 0
Range null

Enable pullup after altitude wait

Note: This parameter functions identically to SIM_GPS1_ENABLE.

SIM_GPS3_HDG_OFS

mGauss
Default 0
Range -400 400

Compass offsets in milligauss on the Z axis

Note: This parameter functions identically to SIM_GPS1_HDG_OFS.

SIM_GPS3_TYPE

null
Default TILT_TYPE_CONTINUOUS
Range null

Tiltrotor type

Note: This parameter configures instance 3. It functions identically to SIM_GPS_TYPE.

SIM_GPS4_ALT_OFS

mGauss
Default 0
Range -400 400

Compass offsets in milligauss on the Z axis

Note: This parameter configures instance 4. It functions identically to SIM_GPS_ALT_OFS.

SIM_GPS4_ENABLE

null
Default 0
Range null

Enable pullup after altitude wait

Note: This parameter functions identically to SIM_GPS1_ENABLE.

SIM_GPS4_HDG_OFS

mGauss
Default 0
Range -400 400

Compass offsets in milligauss on the Z axis

Note: This parameter functions identically to SIM_GPS1_HDG_OFS.

SIM_GPS4_TYPE

null
Default TILT_TYPE_CONTINUOUS
Range null

Tiltrotor type

Note: This parameter configures instance 4. It functions identically to SIM_GPS_TYPE.

SIM_GPS_ACC

m
Default 0.3
Range 0 10

Simulated GPS Accuracy (SIM_GPS_ACC)

Description

SIM_GPS_ACC defines the "Radius of Confusion" for the virtual GPS.

It sets the value reported in the MAVLink GPS_RAW_INT.h_acc field. While it doesn't always add physical noise to the position (see SIM_GPS_NOISE), it tells the EKF how much to trust the position.

Tuning & Behavior

  • Default Value: 0.3 m.
  • Recommendation: Set to 0.1 for "Ideal" GPS or 2.0 to simulate poor signal conditions.

SIM_GPS_ALT_OFS

m
Default 0
Range -100 100

Simulation GPS Altitude Offset (SIM_GPS_ALT_OFS)

Description

SIM_GPS_ALT_OFS injects a constant error into the GPS altitude. This is used to test if the EKF can handle significant differences between its primary altitude source (usually Barometer) and the GPS.

SIM_GPS_BYTELOSS

%
Default 0
Range 0 100

Simulation GPS Byte Loss (SIM_GPS_BYTELOSS)

Description

SIM_GPS_BYTELOSS simulates a flaky or noisy serial cable.

By randomly dropping a percentage of the data packets coming from the GPS, you can test how ArduPilot handles "Checksum Errors" and "Intermittent GPS" failures.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 10. You should see "GPS Glitch" or "GPS 1: Checksum error" messages in your GCS.

SIM_GPS_DELAY

Default 1
Range 0 10

Simulation GPS Delay (SIM_GPS_DELAY)

Description

SIM_GPS_DELAY simulates the processing lag of a real GPS module.

Real GPS units don't report position instantly; there is a calculation delay.

Tuning & Behavior

  • Default Value: 1.
  • Testing: Increasing this can stress-test the EKF's ability to handle delayed measurements.

SIM_GPS_DISABLE

Default 0
Range 0 1

Simulation GPS Disable (SIM_GPS_DISABLE)

Description

SIM_GPS_DISABLE kills the GPS signal.

  • 0: GPS Enabled.
  • 1: GPS Disabled (No Fix).

Tuning & Behavior

  • Default Value: 0.
  • Testing: Use to test Optical Flow, T265 Realsense, or just plain AltHold/Stabilize flight without GPS assistance.

SIM_GPS_DRIFTALT

m/s
Default 0
Range -1 1

Simulation GPS Altitude Drift (SIM_GPS_DRIFTALT)

Description

SIM_GPS_DRIFTALT simulates the atmospheric drift often seen in low-cost GPS modules.

If the GPS reports that the drone is slowly "climbing" or "sinking" while it is actually sitting on the ground, the EKF must decide whether to believe the GPS or the Barometer. This parameter allows you to test that weighting logic.

SIM_GPS_GLITCH

m
Default 0
Range 0 100

Simulated GPS Glitch Offset (SIM_GPS_GLITCH)

Description

SIM_GPS_GLITCH simulates a "GPS Jump."

It adds a sudden, constant offset to the GPS coordinates. This is the best way to test if your EKF_CHECK_SCALE and failsafe settings are tight enough to detect a position jump before the drone flies away.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 10 or 20 meters while in LOITER mode and verify the drone triggers a failsafe rather than banking hard to chase the glitched position.

SIM_GPS_GLITCH_X

m
Default 0
Range -100 100

Simulation GPS Glitch X (SIM_GPS_GLITCH_X)

Description

SIM_GPS_GLITCH_X allows you to inject a GPS failure mid-flight.

By changing this parameter via MAVLink while flying in SITL, you can instantly shift the reported GPS position.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 20 while Loitering. The drone should lean hard to "correct" its position (actually moving away from the true target), then EKF might reject the glitch. Useful for testing EKF failsafe logic.

SIM_GPS_HDG

Default 0
Range 0 3

Simulated GPS Heading Enable (SIM_GPS_HDG)

Description

SIM_GPS_HDG allows the virtual GPS to report a "Moving Base" heading.

This is used for testing GPS-for-Yaw (Dual Antenna) setups in SITL. It tells the simulator to generate the relative position and heading messages that a real U-Blox or NMEA GPS would send when acting as a heading source.

Tuning & Behavior

  • 0: None.
  • 1: NMEA HDT sentence.
  • 2: U-Blox RELPOSNED.
  • 3: NMEA THS sentence.

SIM_GPS_HZ

Hz
Default 5
Range 1 50

Simulation GPS Update Rate (SIM_GPS_HZ)

Description

SIM_GPS_HZ sets the "Refresh Rate" of the simulated GPS.

  • 5 (Default): Standard for most consumer GPS modules.
  • 10: High performance (u-blox M8N/M9N).
  • 50: Industrial RTK systems.

Tuning & Behavior

  • Default Value: 5 Hz.
  • Testing: Use this to verify that your GPS_RATE_MS and EKF settings can handle higher data rates without CPU overload.

SIM_GPS_JAM

Default 0
Range 0 1

Simulated GPS Jamming (SIM_GPS_JAM)

Description

SIM_GPS_JAM simulates a "Denial of Service" attack on your GPS.

When enabled, the GPS continues to report a "3D Fix" (usually), but the signal quality degrades, and the position may drift or freeze, mimicking the behavior of a jammed receiver.

Tuning & Behavior

  • 0: Disabled.
  • 1: Jamming Active.

SIM_GPS_JAM

Default 0
Range 0 1

Simulation GPS Jamming (SIM_GPS_JAM)

Description

SIM_GPS_JAM simulates the drone flying into an area with a GPS jammer.

  • 0: Normal. GPS works as expected.
  • 1: Jammed. The autopilot instantly loses GPS fix, as if the antenna were disconnected. Use this to verify that your drone's EKF correctly fails over to dead-reckoning or triggers an immediate "Land" failsafe.

SIM_GPS_LAG_MS

ms
Default 120
Range 0 500

Simulated GPS Lag (SIM_GPS_LAG_MS)

Description

SIM_GPS_LAG_MS simulates the time it takes for a GPS module to calculate your position and send it over the wire.

Real GPS units always have a delay (latency). This parameter is critical for EKF tuning; the EKF needs to know how "Old" the GPS data is so it can align it with the high-speed IMU data.

Tuning & Behavior

  • Default Value: 120 ms.
  • Recommendation: Set to match your hardware (e.g., U-Blox M8N is typically around 200ms, M9N is closer to 80-120ms).

SIM_GPS_LOCKTIME

s
Default 0
Range 0 120

Simulation GPS Lock Time (SIM_GPS_LOCKTIME)

Description

SIM_GPS_LOCKTIME simulates a "Cold Start."

In SITL, the GPS usually gets a fix instantly. This parameter forces the autopilot to wait for a realistic duration before the GPS reports a valid position. Useful for testing pre-arm procedures.

SIM_GPS_LOG_NUM

Default 0
Range 0 100

Simulated GPS Log Number (SIM_GPS_LOG_NUM)

Description

SIM_GPS_LOG_NUM allows you to replay a specific GPS track from a previous flight log.

If you have a DataFlash log (e.g., 00000012.BIN) where the GPS glitched or behaved weirdly, you can feed that exact GPS data into the simulator to see if the EKF can handle it better with different settings.

Tuning & Behavior

  • Default Value: 0 (Disabled).
  • Usage: Set SIM_GPS_TYPE to 7 (File) and set this parameter to the log index you want to replay.

SIM_GPS_NOISE

m
Default 0
Range 0 10

Simulated GPS Noise (SIM_GPS_NOISE)

Description

SIM_GPS_NOISE adds random position jitter to the virtual GPS.

Unlike SIM_GPS_ACC (which only reports accuracy), this parameter actually moves the reported latitude/longitude/altitude by a random amount in every frame. This is the primary tool for testing how much GPS "Fuzz" your EKF can handle before the drone starts to wander or failsafes.

Tuning & Behavior

  • Default Value: 0 (Perfect GPS).
  • Recommendation: Set to 0.5 or 1.0 to simulate a realistic low-cost GPS in an open field. Set to 3.0+ to simulate urban canyon environments.

SIM_GPS_NUMSATS

Default 10
Range 0 30

Simulation GPS Satellite Count (SIM_GPS_NUMSATS)

Description

SIM_GPS_NUMSATS allows you to simulate "Signal Shading" or poor sky visibility.

ArduPilot's EKF requires a minimum number of satellites to maintain a high-quality position fix. By reducing this value in SITL, you can test how the drone behaves when it enters a "Degraded GPS" state.

  • 10 (Default): Healthy fix.
  • 5: Poor fix. EKF may report warnings.
  • 3: Fix lost. Drone will switch to non-GPS modes.

SIM_GPS_POS

m
Default 0
Range -5 5

Simulation GPS Position Offset (SIM_GPS_POS)

Description

SIM_GPS_POS defines the mounting location of the virtual GPS antenna.

See GPS_POS for details on why antenna offsets are critical for flight stability.

SIM_GPS_TYPE

Default 1
Range 0 26

Simulation GPS Type (SIM_GPS_TYPE)

Description

SIM_GPS_TYPE tells the simulator which "Language" to use when sending data to the autopilot.

  • 1: u-blox (Standard). The most common GPS type.
  • 5: NMEA. Generic serial data.
  • 9: DroneCAN. Simulates a CAN-bus GPS.
  • 14: MAVLink.

SIM_GPS_VERR

m/s
Default 0
Range 0 5

Simulation GPS Velocity Error (SIM_GPS_VERR)

Description

SIM_GPS_VERR simulates a GPS receiver that reports incorrect speeds.

This is a common failure mode in real-world "Urban Canyons," where signal multipath can cause the GPS to think the drone is moving at 2 m/s even when it is perfectly still. This parameter helps you test the EKF's ability to reject bad velocity data and rely more on the accelerometers.

SIM_GRPE_ENABLE

Default 0
Range 0 1

Simulation Gripper Enable (SIM_GRPE_ENABLE)

Description

SIM_GRPE_ENABLE activates a virtual robotic gripper.

This allows you to test "Pick and Place" missions in SITL. When enabled, the drone can physically attach to objects (like a virtual package) and carry them through the air, accounting for the added weight and inertia in the physics model.

SIM_GRPE_PIN

Default 0
Range 1 32

Simulated EPM Gripper Pin (SIM_GRPE_PIN)

Description

SIM_GRPE_PIN links the virtual EPM magnet to an output channel.

SIM_GRPS_ENABLE

Default 0
Range 0 1

Gripper Servo Sim Enable (SIM_GRPS_ENABLE)

Description

SIM_GRPS_ENABLE adds a functional virtual gripper to the drone.

This allows you to test "Cargo Hold" operations. The simulator models a servo-driven jaw that can pick up and drop a 1kg load when on the ground.

Tuning & Behavior

  • 0: Disabled.
  • 1: Enabled.

SIM_GRPS_GRAB

PWM
Default 1100
Range 1000 2000

Gripper Grab PWM (SIM_GRPS_GRAB)

Description

SIM_GRPS_GRAB sets the "Closed" position for the virtual gripper.

SIM_GRPS_PIN

Default -1
Range -1 16

Gripper Servo Pin (SIM_GRPS_PIN)

Description

SIM_GRPS_PIN connects the virtual gripper to a flight controller output.

Set this to match your SERVOx_FUNCTION = 28 (Gripper) channel. When ArduPilot moves that servo, the simulator will open or close the virtual jaws.

Tuning & Behavior

  • Default Value: -1 (Disabled).

SIM_GRPS_RELEASE

PWM
Default 1900
Range 1000 2000

Gripper Release PWM (SIM_GRPS_RELEASE)

Description

SIM_GRPS_RELEASE sets the "Open" position for the virtual gripper.

SIM_GRPS_REVERSE

Default 0
Range 0 1

Gripper Reverse (SIM_GRPS_REVERSE)

Description

SIM_GRPS_REVERSE swaps the open and closed states of the virtual jaws.

SIM_GYR1_BIAS

deg/s
Default 0
Range -5 5

Simulation Gyro 1 Bias (SIM_GYR1_BIAS)

Description

SIM_GYR1_BIAS simulates "Gyro Drift."

Real-world gyroscopes are sensitive to temperature and time. If you leave a drone sitting on a table, the reported rotation rate might not be exactly zero. This drift is the primary cause of "Horizon Tilt" in flight. ArduPilot's EKF is designed to learn and cancel this drift.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 1.0 (1 degree per second). You can watch the EKF "innovations" in your logs as the autopilot detects and attempts to compensate for this fake drift.

SIM_GYR1_RND

deg/s
Default 0
Range 0 10.0

Simulated Gyroscope 1 Noise (SIM_GYR1_RND)

Description

SIM_GYR1_RND injects artificial noise into the simulated primary gyroscope.

This is used to test how "twitchy" or unstable the drone's attitude control becomes when the gyro data is imperfect. High noise levels can cause the drone to oscillate or lose orientation entirely.

The Engineer's View

Adds Gaussian noise (σ) to the body-frame rotational rate:
$$ \omega\_{read} = \omega\_{true} + \mathcal{N}(0, \text{SIM\_GYR1\_RND}) $$

Tuning & Behavior

  • Default Value: 0
  • Effect of Increasing: The drone's attitude (roll/pitch/yaw) will appear to vibrate or "jitter" in the GCS HUD, and the EKF may trigger "high gyro noise" warnings.

SIM_GYR1_SCALE

Default 0
Range -0.1 0.1

Simulation Gyro 1 Scale (SIM_GYR1_SCALE)

Description

SIM_GYR1_SCALE simulates a sensitivity error on the rotation axis.

If you rotate the drone by exactly 360 degrees, a sensor with a scale error might report 365 or 355 degrees. This is important for verifying high-rate aerobatic performance.

SIM_GYR2_BIAS

deg/s
Default 0
Range -5 5

Simulation Gyro 2 Bias (SIM_GYR2_BIAS)

Description

SIM_GYR2_BIAS simulates drift on the secondary IMU.

See SIM_GYR1_BIAS for details.

SIM_GYR2_RND

null
Default 0
Range null

Gyro 2 motor noise factor

Note: This parameter functions identically to SIM_GYR1_RND.

SIM_GYR2_SCALE

Default 0
Range -0.1 0.1

Simulation Gyro 2 Scale (SIM_GYR2_SCALE)

Description

SIM_GYR2_SCALE simulates sensitivity errors on the secondary IMU.

See SIM_GYR1_SCALE for details.

SIM_GYR3_BIAS

deg/s
Default 0
Range -5 5

Simulation Gyro 3 Bias (SIM_GYR3_BIAS)

Description

SIM_GYR3_BIAS simulates drift on the tertiary IMU.

See SIM_GYR1_BIAS for details.

SIM_GYR3_RND

null
Default 0
Range null

Gyro 3 motor noise factor

Note: This parameter functions identically to SIM_GYR1_RND.

SIM_GYR3_SCALE

Default 0
Range null

Gyro 3 scaling factor

Note: This parameter configures instance 3. It functions identically to SIM_GYR1_SCALE.

SIM_GYR4_BIAS

Default 0
Range null

Fourth Gyro bias on Z axis

Note: This parameter configures instance 4. It functions identically to SIM_GYR1_BIAS.

SIM_GYR4_RND

null
Default 0
Range null

Gyro 4 motor noise factor

Note: This parameter functions identically to SIM_GYR1_RND.

SIM_GYR4_SCALE

Default 0
Range null

Gyro 4 scaling factor

Note: This parameter configures instance 4. It functions identically to SIM_GYR1_SCALE.

SIM_GYR5_BIAS

Default 0
Range null

Fifth Gyro bias on Z axis

Note: This parameter configures instance 5. It functions identically to SIM_GYR1_BIAS.

SIM_GYR5_RND

null
Default 0
Range null

Gyro 5 motor noise factor

Note: This parameter functions identically to SIM_GYR1_RND.

SIM_GYR5_SCALE

Default 0
Range null

Gyro 5 scaling factor

Note: This parameter configures instance 5. It functions identically to SIM_GYR1_SCALE.

SIM_GYR_FAIL_MSK

Default 0
Range 0 7

Simulated Gyroscope Failure Mask (SIM_GYR_FAIL_MSK)

Description

SIM_GYR_FAIL_MSK kills specific gyroscopes in the simulator.

This is critical for testing the "vibration failsafe" and EKF lane switching logic.

  • Bit 0 (1): Fail Gyro 1
  • Bit 1 (2): Fail Gyro 2
  • Bit 2 (4): Fail Gyro 3

Tuning & Behavior

  • Default Value: 0
  • Recommendation: Use in conjunction with SIM_ACC_FAIL_MSK to simulate a complete IMU failure.

SIM_GYR_FILE_RW

Default 0
Range 0 3

Simulated Gyroscope File Read/Write (SIM_GYR_FILE_RW)

Description

SIM_GYR_FILE_RW works exactly like SIM_ACC_FILE_RW but for the gyroscope.

Use this to replay real-world gyro noise (propeller vibration) into the simulator. This is the gold standard for testing Harmonic Notch Filter settings without risking a crash.

Tuning & Behavior

  • Default Value: 0.
  • Procedure:
    1. Set to 2 (Write).
    2. Fly/Hover for 1 minute.
    3. Copy the generated file to your SITL directory.
    4. Set to 1 (Read) and run SITL.

SIM_IE24_ENABLE

Default 0
Range 0 1

Simulated IE24 Fuel Cell Enable (SIM_IE24_ENABLE)

Description

SIM_IE24_ENABLE adds a virtual Hydrogen Fuel Cell to the simulation.

This allows you to test the telemetry feedback (tank pressure, stack voltage, error states) of an Intelligent Energy 2.4kW unit without needing the expensive hardware.

Tuning & Behavior

  • 0: Disabled.
  • 1: Enabled.

SIM_IE24_ERROR

Default 0
Range 0 4294967295

Simulated IE24 Error Code (SIM_IE24_ERROR)

Description

SIM_IE24_ERROR simulates a hardware failure.

By setting this to a valid IE24 error bitmask, you can verify that the GCS displays the correct warning message (e.g. "Low Hydrogen Pressure" or "Stack Over-temp").

Tuning & Behavior

  • Default Value: 0.

SIM_IE24_STATE

Default 0
Range 0 10

Simulated IE24 State (SIM_IE24_STATE)

Description

SIM_IE24_STATE overrides the fuel cell logic.

  • 0: Auto (Normal operation).
  • 1: Starting.
  • 2: Running.
  • 4: Fault.

Tuning & Behavior

  • Default Value: 0.

SIM_IMUT1_ENABLE

Default 0
Range 0 1

Simulated IMU 1 Thermal Enable (SIM_IMUT1_ENABLE)

Description

SIM_IMUT1_ENABLE activates the simulated heat-up process for the first IMU.

When enabled, the IMU's reported temperature will follow the curve defined by SIM_IMUT_START, END, and TCONST. This is useful for verifying that your INS_TCAL1_ parameters (learned during a real temp cal) correctly remove the bias drift in the simulator.

Tuning & Behavior

  • 0: Disabled (IMU stays at constant temperature).
  • 1: Enabled.

SIM_IMUT1_TMAX

degC
Default 80
Range -50 80

Simulation IMU Temperature Max (SIM_IMUT1_TMAX)

Description

SIM_IMUT1_TMAX defines the upper bound for the IMU thermal model.

SIM_IMUT1_TMIN

degC
Default -10
Range -50 80

Simulation IMU Temperature Min (SIM_IMUT1_TMIN)

Description

SIM_IMUT1_TMIN defines the lower bound for simulating IMU thermal noise and bias shifts.

SIM_IMUT2_ENABLE

null
Default 0
Range null

Enable pullup after altitude wait

Note: This parameter functions identically to SIM_IMUT1_ENABLE.

SIM_IMUT2_TMAX

degC
Default 70
Range -70 80

Temperature calibration max

Note: This parameter functions identically to SIM_IMUT1_TMAX.

SIM_IMUT2_TMIN

degC
Default 0
Range -70 80

Temperature calibration min

Note: This parameter functions identically to SIM_IMUT1_TMIN.

SIM_IMUT3_ENABLE

null
Default 0
Range null

Enable pullup after altitude wait

Note: This parameter functions identically to SIM_IMUT1_ENABLE.

SIM_IMUT3_TMAX

degC
Default 70
Range -70 80

Temperature calibration max

Note: This parameter functions identically to SIM_IMUT1_TMAX.

SIM_IMUT3_TMIN

degC
Default 0
Range -70 80

Temperature calibration min

Note: This parameter functions identically to SIM_IMUT1_TMIN.

SIM_IMUT4_ENABLE

null
Default 0
Range null

Enable pullup after altitude wait

Note: This parameter functions identically to SIM_IMUT1_ENABLE.

SIM_IMUT4_TMAX

degC
Default 70
Range -70 80

Temperature calibration max

Note: This parameter functions identically to SIM_IMUT1_TMAX.

SIM_IMUT4_TMIN

degC
Default 0
Range -70 80

Temperature calibration min

Note: This parameter functions identically to SIM_IMUT1_TMIN.

SIM_IMUT5_ENABLE

null
Default 0
Range null

Enable pullup after altitude wait

Note: This parameter functions identically to SIM_IMUT1_ENABLE.

SIM_IMUT5_TMAX

degC
Default 70
Range -70 80

Temperature calibration max

Note: This parameter functions identically to SIM_IMUT1_TMAX.

SIM_IMUT5_TMIN

degC
Default 0
Range -70 80

Temperature calibration min

Note: This parameter functions identically to SIM_IMUT1_TMIN.

SIM_IMUT_END

degC
Default 45
Range -40 100

Simulated IMU Final Temperature (SIM_IMUT_END)

Description

SIM_IMUT_END sets the target temperature that the flight controller will eventually reach after it has been running for a while (due to CPU heat and internal electronics).

Tuning & Behavior

  • Default Value: 45 °C.

SIM_IMUT_FIXED

degC
Default 0
Range -40 100

Simulated IMU Fixed Temperature (SIM_IMUT_FIXED)

Description

SIM_IMUT_FIXED forces the virtual IMU to stay at a specific temperature.

If set to a non-zero value, the IMU temperature will not follow the curve defined by SIM_IMUT_START and SIM_IMUT_END. This is useful for testing sensor bias at a specific operating point without waiting for the heat-up cycle.

Tuning & Behavior

  • 0: Disabled (Use dynamic thermal curve).
  • Non-Zero: Fixed temperature in Celsius.

SIM_IMUT_START

degC
Default 25
Range -40 100

Simulated IMU Start Temperature (SIM_IMUT_START)

Description

SIM_IMUT_START defines the "Ambient Temperature" when the simulator starts.

SITL can simulate the heating of the flight controller over time. This parameter sets the baseline. If you want to test how your drone handles a sub-zero cold start, you can set this to -10.

Tuning & Behavior

  • Default Value: 25 °C.
  • Usage: Use this in conjunction with SIM_IMUT_END and SIM_IMUT_TCONST to create a thermal warm-up profile.

SIM_IMUT_TCONST

s
Default 300
Range 1 3600

Simulated IMU Thermal Time Constant (SIM_IMUT_TCONST)

Description

SIM_IMUT_TCONST determines how fast the flight controller heats up.

It defines the "Slope" of the temperature curve. A value of 300 seconds (5 minutes) means the drone will reach its steady-state temperature fairly slowly, mimicking a real flight controller on a workbench.

The Mathematics

The temperature $T(t)$ at time $t$ is modeled as an exponential approach:

$$ T(t) = T\_{start} + (T\_{end} - T\_{start}) \times (1 - e^{-t / \tau}) $$

Where $\tau$ is the SIM_IMUT_TCONST.

SIM_IMU_COUNT

Default 2
Range 1 3

Simulated IMU Count (SIM_IMU_COUNT)

Description

SIM_IMU_COUNT sets the number of virtual internal sensors.

Modern flight controllers often have 2 or 3 IMUs for safety. This parameter allows SITL to mimic that redundancy. You can then use SIM_ACCELx_FAIL to kill one sensor and see how the autopilot handles it.

Tuning & Behavior

  • Default Value: 2.
  • Recommendation: Set to 2 or 3 to test EKF lane switching logic.
  • Reboot Required: Yes.

SIM_IMU_ORIENT

Default 0
Range 0 38

Simulated IMU Orientation (SIM_IMU_ORIENT)

Description

SIM_IMU_ORIENT sets the physical "Heading" of the virtual sensors.

By default (0), the IMU is aligned with the drone's nose. If you want to test how ArduPilot handles an IMU that is mounted upside down or rotated 90 degrees, you can change this parameter and then verify that you can still calibrate and fly successfully using AHRS_ORIENTATION.

Tuning & Behavior

  • Default Value: 0 (None).
  • Recommendation: Leave at 0 for standard tests. Use values like 8 (Roll 180) to test an inverted flight controller.

SIM_IMU_POS

m
Default 0
Range 0 5

Simulation IMU Position Offset (SIM_IMU_POS)

Description

SIM_IMU_POS simulates an IMU that is not mounted exactly at the center of gravity (COG).

When a drone rotates, any sensor away from the COG experiences "Centripetal Acceleration." If ArduPilot doesn't know about this offset (configured via INS_POS_X/Y/Z), the EKF will get confused and report incorrect velocity. This parameter allows you to test the compensation for these "Lever Arm" effects.

SIM_INIT_ALT_OFS

m
Default 0
Range -100 100

Simulation Initial Alt Offset (SIM_INIT_ALT_OFS)

Description

SIM_INIT_ALT_OFS allows you to start the simulation with the drone at a specific height above the ground. Useful for testing in-air resets or high-altitude drop launches.

SIM_INIT_LAT_OFS

deg
Default 0
Range -1 1

Simulated Initial Latitude Offset (SIM_INIT_LAT_OFS)

Description

SIM_INIT_LAT_OFS allows you to test what happens if the "map" shifts under the drone.

It adds a constant offset to the GPS position reported by the simulator, effectively moving the world origin.

Tuning & Behavior

  • Default Value: 0.

SIM_INIT_LON_OFS

deg
Default 0
Range -1 1

Simulated Initial Longitude Offset (SIM_INIT_LON_OFS)

Description

SIM_INIT_LON_OFS shifts the GPS longitude origin. See SIM_INIT_LAT_OFS.

Tuning & Behavior

  • Default Value: 0.

SIM_INS_THR_MIN

%
Default 0.1
Range 0 1

Simulated INS Noise Throttle Min (SIM_INS_THR_MIN)

Description

SIM_INS_THR_MIN defines when the "Shaking" starts.

Real drones vibrate more when the motors are spinning fast. This parameter tells SITL to only add motor-induced noise when the throttle is above a certain percentage (e.g. 10%). On the ground at zero throttle, the IMUs will remain clean.

Tuning & Behavior

  • Default Value: 0.1 (10% throttle).

SIM_JSON_MASTER

Default 0
Range 0 4294967295

Simulated JSON Master (SIM_JSON_MASTER)

Description

SIM_JSON_MASTER enables the "External Physics" bridge.

Instead of SITL calculating the drone's movements, it can send the motor outputs to a high-fidelity simulator (like Gazebo, AirSim, or Webots) and get the position/sensor data back over a JSON socket. This parameter sets the IP address of that external simulator.

Tuning & Behavior

  • Default Value: 127.0.0.1 (Localhost).
  • Usage: Only active if the SITL build includes the JSON backend.

SIM_LED_LAYOUT

Default 0
Range 0 10

Simulation LED Layout (SIM_LED_LAYOUT)

Description

SIM_LED_LAYOUT defines the number and position of virtual status LEDs in SITL. This is primarily used for verifying LED driver logic and patterns (like those for the SkyViper or ProfiLED) in a simulated environment.

SIM_LOOP_DELAY

ms
Default 0
Range 0 100

Simulated Loop Delay (SIM_LOOP_DELAY)

Description

SIM_LOOP_DELAY simulates a "Slow Processor."

If you set this to 5ms, every single logic loop in the autopilot will take 5ms longer than usual. This is a great way to test the safety margins of your loop rate and see at what point the drone becomes unflyable due to latency.

SIM_MAG1_DEVID

Default 0
Range 0 16777216

Simulated Magnetometer 1 Device ID (SIM_MAG1_DEVID)

Description

SIM_MAG1_DEVID sets the unique hardware identifier for the virtual compass.

This is usually read-only or managed by SIM_MAG_SAVE_IDS. However, developers can manually set this to test how the OS handles specific sensor types (e.g. simulating a specific I2C address conflict).

Tuning & Behavior

  • Default Value: 0 (Auto-generated).

SIM_MAG1_DIA

Default 0
Range -0.2 0.2

Simulation Magnetometer 1 Diagonal (SIM_MAG1_DIA)

Description

SIM_MAG1_DIA simulates "Soft Iron" interference.

Soft iron effects are caused by materials that distort magnetic fields but are not themselves magnets (like iron or nickel). This distorts the magnetic "sphere" into an "ellipsoid." ArduPilot's advanced calibration routine calculates these diagonal scaling factors to fix this distortion.

SIM_MAG1_FAIL

Default 0
Range 0 1

Simulation Compass 1 Failure (SIM_MAG1_FAIL)

Description

SIM_MAG1_FAIL kills the first compass sensor.

  • 0: Healthy.
  • 1: Failed. The sensor stops reporting data.

Tuning & Behavior

  • Testing: Use this to verify that your drone successfully fails over to the second compass (if available) or switches to GSF (GPS-based yaw) without crashing.

SIM_MAG1_ODI

Default 0
Range -0.2 0.2

Simulation Magnetometer 1 Off-Diagonal (SIM_MAG1_ODI)

Description

SIM_MAG1_ODI simulates complex magnetic distortions.

While SIM_MAG1_DIA scales the X, Y, and Z axes independently, ODI (Off-Diagonal) terms simulate how a magnetic field in one axis (e.g. X) can bleed into another axis (e.g. Y). This represents a highly non-linear or asymmetric magnetic environment.

SIM_MAG1_OFS

mGauss
Default 0
Range -100 100

Simulation Magnetometer 1 Offset (SIM_MAG1_OFS)

Description

SIM_MAG1_OFS simulates "Hard Iron" interference.

Hard iron effects are caused by static magnetic fields on the drone (like a magnetized screw or the metal frame). This offsets the magnetic reading in a constant direction. This is what you are calibrating when you perform the "Compass Dance."

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 50. The drone will report "Compass Variance" until you perform a compass calibration in SITL.

SIM_MAG1_ORIENT

Default 0
Range 0 38

Simulated Magnetometer 1 Orientation (SIM_MAG1_ORIENT)

Description

SIM_MAG1_ORIENT sets the physical rotation of the virtual compass.

If you simulate a GPS/Compass module mounted with the arrow pointing backwards (Yaw 180), you must set this parameter to match.

Tuning & Behavior

  • Default Value: 0 (None).

SIM_MAG1_SCALING

Default 1.0
Range 0.5 1.5

Simulated Magnetometer 1 Scaling (SIM_MAG1_SCALING)

Description

SIM_MAG1_SCALING simulates a mis-calibrated compass.

By setting this to 1.1 or 0.9, you can test if the "Compass Motel" (onboard calibration) or the EKF can learn and correct for the scale factor error.

Tuning & Behavior

  • Default Value: 1.0.

SIM_MAG2_DEVID

null
Default 0
Range null

Airspeed ID

Note: This parameter functions identically to SIM_MAG1_DEVID.

SIM_MAG2_DIA

Default 0
Range -0.2 0.2

Simulation Magnetometer 2 Diagonal (SIM_MAG2_DIA)

Description

SIM_MAG2_DIA simulates a distorted magnetic field on the secondary compass.

See SIM_MAG1_DIA for details.

SIM_MAG2_FAIL

null
Default 0
Range null

MAG2 Failure

Note: This parameter functions identically to SIM_MAG1_FAIL.

SIM_MAG2_ODI

Default 0
Range -0.2 0.2

Simulation Magnetometer 2 Off-Diagonal (SIM_MAG2_ODI)

Description

SIM_MAG2_ODI simulates complex magnetic twisting on the secondary compass.

See SIM_MAG1_ODI for details.

SIM_MAG2_OFS

mGauss
Default 0
Range -100 100

Simulation Magnetometer 2 Offset (SIM_MAG2_OFS)

Description

SIM_MAG2_OFS simulates hard-iron interference on the secondary compass.

This is useful for testing the EKF's ability to handle inconsistent compass data. If Compass 1 is perfect and Compass 2 has a massive offset, the EKF should (ideally) reject Compass 2 or learn the offset.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 100 to simulate a magnetized screw near the second GPS puck.

SIM_MAG2_ORIENT

null
Default AC_PRECLAND_ORIENT_DEFAULT
Range null

Camera Orientation

Note: This parameter functions identically to SIM_MAG1_ORIENT.

SIM_MAG2_SCALING

null
Default 1.0f
Range null

RPM scaling

Note: This parameter functions identically to SIM_MAG1_SCALING.

SIM_MAG3_DEVID

null
Default 0
Range null

Airspeed ID

Note: This parameter functions identically to SIM_MAG1_DEVID.

Default 0
Range null

Note: This parameter configures instance 3. It functions identically to SIM_MAG1_DIA.

SIM_MAG3_FAIL

null
Default 0
Range null

MAG3 Failure

Note: This parameter functions identically to SIM_MAG1_FAIL.

Default 0
Range null

Note: This parameter configures instance 3. It functions identically to SIM_MAG1_ODI.

SIM_MAG3_OFS

mGauss
Default 0
Range -100 100

Simulation Magnetometer 3 Offset (SIM_MAG3_OFS)

Description

SIM_MAG3_OFS simulates hard-iron interference on the third compass.

See SIM_MAG1_OFS for details.

SIM_MAG3_ORIENT

null
Default AC_PRECLAND_ORIENT_DEFAULT
Range null

Camera Orientation

Note: This parameter functions identically to SIM_MAG1_ORIENT.

SIM_MAG3_SCALING

null
Default 1.0f
Range null

RPM scaling

Note: This parameter functions identically to SIM_MAG1_SCALING.

SIM_MAG4_DEVID

null
Default 0
Range null

Airspeed ID

Note: This parameter functions identically to SIM_MAG1_DEVID.

SIM_MAG5_DEVID

null
Default 0
Range null

Airspeed ID

Note: This parameter functions identically to SIM_MAG1_DEVID.

SIM_MAG6_DEVID

null
Default 0
Range null

Airspeed ID

Note: This parameter functions identically to SIM_MAG1_DEVID.

SIM_MAG7_DEVID

null
Default 0
Range null

Airspeed ID

Note: This parameter functions identically to SIM_MAG1_DEVID.

SIM_MAG8_DEVID

null
Default 0
Range null

Airspeed ID

Note: This parameter functions identically to SIM_MAG1_DEVID.

SIM_MAG_ALY

mGauss
Default 0
Range -100 100

Simulation Magnetic Anomaly (SIM_MAG_ALY)

Description

SIM_MAG_ALY simulates flying over a large iron object (like a bridge or underground pipe).

Unlike MAG_OFS, which is attached to the drone, MAG_ALY is a disturbance in the "World" that only affects the drone when it is in a specific location. Useful for testing the EKF's resilience to sudden, external heading shifts.

SIM_MAG_ALY_HGT

m
Default 0
Range 0 1000

Simulated Magnetic Anomaly Height (SIM_MAG_ALY_HGT)

Description

SIM_MAG_ALY_HGT creates a virtual "Magnetic Distortion Field" at a specific altitude.

This is useful for simulating flying near a large steel structure (like a bridge or tower). You can test if the EKF correctly rejects the bad compass data or if the drone starts to toilet-bowl.

Tuning & Behavior

  • Default Value: 0.

SIM_MAG_DELAY

ms
Default 0
Range 0 100

Simulation Compass Delay (SIM_MAG_DELAY)

Description

SIM_MAG_DELAY simulates slow compass updates or high-latency I2C buses.

Real compasses often sample slower than the EKF's loop rate. This parameter tests if the EKF can correctly align delayed compass samples with the corresponding IMU poses.

SIM_MAG_MOT

Default 0
Range 0 1

Simulation Compass Motor Interference (SIM_MAG_MOT)

Description

SIM_MAG_MOT simulates "CompassMot" effects.

In real drones, the high-current wires going to the motors produce magnetic fields that can bias the compass. As you increase throttle, the compass heading "twists." This parameter allows you to simulate this effect to test the efficacy of the CompassMot calibration.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 0.5. Perform a full throttle punch in Loiter. The drone will likely rotate (yaw) unintentionally as the compass drifts under load.

SIM_MAG_NOISE

mGauss
Default 0
Range 0 100

Simulated Magnetometer Noise (SIM_MAG_NOISE)

Description

SIM_MAG_NOISE adds random jitter to the compass readings.

Real compasses are very clean sensors, but they are affected by surrounding electronics. This parameter simulates that background electromagnetic noise.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Set to 5-10 mGauss for realistic testing.

SIM_MAG_RND

Gauss
Default 0
Range 0 1

Simulated Magnetometer Noise (SIM_MAG_RND)

Description

SIM_MAG_RND adds static fuzz to the compass readings.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Increase this to see how much noise the EKF can tolerate before triggering a "Compass Variance" error.

SIM_MAG_SAVE_IDS

Default 0
Range 0 1

Simulated Magnetometer Save IDs (SIM_MAG_SAVE_IDS)

Description

SIM_MAG_SAVE_IDS makes the virtual compasses persistent.

Normally, every time you restart SITL, it generates new random "Device IDs" for the sensors. This forces you to re-calibrate the compass every time. If you enable this, the simulator saves the IDs, allowing you to keep your calibration data.

Tuning & Behavior

  • 0: Disabled (New IDs on boot).
  • 1: Enabled (Save IDs).

SIM_ODOM_ENABLE

Default 0
Range 0 1

Simulation Odometry Enable (SIM_ODOM_ENABLE)

Description

SIM_ODOM_ENABLE activates a virtual Visual Odometry (VO) sensor.

This simulates a camera-based system (like an Intel Realsense) that tracks the drone's position by looking at the ground. Useful for testing autonomous navigation in GPS-denied environments without needing a full Vicon setup.

SIM_OH_MASK

Default 0
Range 0 65535

SIM-on-Hardware Output Mask (SIM_OH_MASK)

Description

SIM_OH_MASK allows "Hardware-in-the-Loop" behavior without external software.

If you flash the SITL binary onto a real Pixhawk ("Sim on Hardware"), the physics run on the CPU, but the servo outputs are normally disabled. This mask enables specific physical pins so you can drive real servos or motors while flying a virtual drone.

Tuning & Behavior

  • Default Value: 0 (All outputs disabled).
  • Bit 0 (1): Enable Servo 1.
  • Bit 1 (2): Enable Servo 2.

SIM_OH_RELAY_MSK

Default 0
Range 0 255

SIM-on-Hardware Relay Mask (SIM_OH_RELAY_MSK)

Description

SIM_OH_RELAY_MSK enables physical relay pins during "Sim on Hardware."

Tuning & Behavior

  • Default Value: 0.

SIM_OPOS_ALT

m
Default 584.0
Range 0 10000

Simulated Original Position (Altitude) (SIM_OPOS_ALT)

Description

SIM_OPOS_ALT sets the spawn height Above Mean Sea Level (AMSL).

Tuning & Behavior

  • Default Value: 584.0 m (Canberra elevation).
  • Important: If you change Lat/Lng to a coastal city but leave this at 584m, your drone will spawn 584m in the air!

SIM_OPOS_HDG

deg
Default 353.0
Range 0 360

Simulated Original Position (Heading) (SIM_OPOS_HDG)

Description

SIM_OPOS_HDG sets the direction the vehicle faces when it spawns.

  • 0: North
  • 90: East
  • 180: South
  • 270: West

Tuning & Behavior

  • Default Value: 353.0 degrees.
  • Recommendation: Align this with the "virtual runway" at your test site to make takeoff easier.

SIM_OPOS_LAT

deg
Default -35.363261
Range -90 90

Simulated Original Position (Latitude) (SIM_OPOS_LAT)

Description

SIM_OPOS_LAT sets the home location where your drone spawns in the simulator.

  • Default: CMAC (Canberra Model Aircraft Club) in Australia.
  • Usage: Change this to your local flying field's coordinates to test missions in a familiar environment.

Tuning & Behavior

  • Default Value: -35.363261 (Canberra).
  • Recommendation: Use a tool like Mission Planner's "Set Home" feature, which updates this parameter automatically.

SIM_OPOS_LNG

deg
Default 149.165230
Range -180 180

Simulated Original Position (Longitude) (SIM_OPOS_LNG)

Description

SIM_OPOS_LNG sets the starting longitude for the simulation.

Tuning & Behavior

  • Default Value: 149.165230 (Canberra).

SIM_OSD_COLUMNS

Default 30
Range 1 50

Simulated OSD Columns (SIM_OSD_COLUMNS)

Description

SIM_OSD_COLUMNS defines the width of the virtual OSD screen.

Tuning & Behavior

  • Default Value: 30 columns.

SIM_OSD_ROWS

Default 16
Range 1 30

Simulated OSD Rows (SIM_OSD_ROWS)

Description

SIM_OSD_ROWS defines the height of the virtual OSD screen.

This is used for testing MSP (MultiWii Serial Protocol) OSD layouts in SITL. By changing this, you can simulate different goggle resolutions or display types.

Tuning & Behavior

  • Default Value: 16 rows.
  • Common Settings: 13 or 16 rows for standard analog/digital systems.

SIM_PARA_ENABLE

Default 0
Range 0 1

Simulated Parachute Enable (SIM_PARA_ENABLE)

Description

SIM_PARA_ENABLE adds a drag-inducing chute to the physics model.

When the parachute is "deployed" (via SIM_PARA_PIN), the drone's drag coefficient increases massively, causing it to drift down slowly rather than crash. This is vital for testing CHUTE_ parameters and failsafe triggers.

Tuning & Behavior

  • 0: Disabled.
  • 1: Enabled.

SIM_PARA_PIN

Default 0
Range 0 100

Simulated Parachute Pin (SIM_PARA_PIN)

Description

SIM_PARA_PIN connects the virtual parachute to an output channel.

Set this to match your CHUTE_SERVO_ON value. When that pin goes high, the simulator deploys the chute.

SIM_PIN_MASK

Default 0
Range 0 65535

Simulated GPIO Pin Mask (SIM_PIN_MASK)

Description

SIM_PIN_MASK tells the simulator which "Digital Pins" it should pretend exist.

This allows you to test things like Relay control, Camera triggering, or specialized hardware switches without physical wires.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Match the pins you have configured in your RELAY_PIN or CAM_FEEDBACK_PIN parameters.

SIM_PLD_ALT_LMT

m
Default 15
Range 0 100

Simulation Precision Landing Max Altitude (SIM_PLD_ALT_LMT)

Description

SIM_PLD_ALT_LMT simulates the "Range Limit" of your Precision Landing sensor (e.g. IR-Lock).

Real sensors have a limited effective range. If the drone is too high, the camera or sensor cannot see the beacon on the ground. This parameter tells the simulator to stop reporting valid target data when the drone climbs above this altitude.

Tuning & Behavior

  • Default: 15 meters.
  • Usage: Set this to match the datasheet of your real sensor (e.g. IR-Lock MarkOne is typically effective up to ~15m in daylight).
  • Testing: Fly above this limit in SITL to verify that your failsafe or "Lost Target" logic engages correctly.

SIM_PLD_DIST_LMT

m
Default 10
Range 0 100

Simulation Precision Landing Lateral Range (SIM_PLD_DIST_LMT)

Description

SIM_PLD_DIST_LMT simulates the "Field of View" (FOV) constraint of your Precision Landing sensor.

Cameras and IR sensors can only see a certain width. If the drone is too far to the side of the target, the beacon will fall out of the camera's frame. This parameter sets that lateral limit in meters.

Tuning & Behavior

  • Default: 10 meters.
  • Physics: This creates a virtual "cone" or cylinder of detection above the target. If the horizontal distance between the drone and the SIM_PLD_LAT/LON target is greater than this value, the sensor reports "No Target."

SIM_PLD_ENABLE

Default 0
Range 0 1

Simulated Precision Landing Enable (SIM_PLD_ENABLE)

Description

SIM_PLD_ENABLE adds a virtual infrared beacon or visual target to the world.

This is the primary way to test "Precision Landing" (PLND_ENABLE) in the simulator. It simulates the data from an IR-Lock camera or a downward-facing visual system.

Tuning & Behavior

  • Default Value: 0 (Disabled).
  • 1: Enabled. The target will spawn at the coordinates defined by SIM_PLD_LAT/LON.

SIM_PLD_HEIGHT

m
Default 0
Range 0 100

Simulated Precision Landing Height (SIM_PLD_HEIGHT)

Description

SIM_PLD_HEIGHT defines the vertical position of the landing target (e.g., a rooftop, a landing platform, or a pole-mounted beacon) in SITL.

This allows you to test precision landing algorithms on elevated platforms rather than just on the flat ground.

Tuning & Behavior

  • Default: 0 (Target is at ground level).
  • Usage: Set to the desired height in meters. The virtual sensor (IR-Lock) will report the target's position based on this height.

SIM_PLD_LAT

deg
Default 0
Range -90 90

Simulated Precision Landing Latitude (SIM_PLD_LAT)

Description

SIM_PLD_LAT defines the north/south coordinate of the landing target beacon used in the Precision Landing simulation.

This allows you to place the virtual beacon at a specific location on the map to test how the drone detects and navigates toward it from different approach angles.

Tuning & Behavior

  • Default: 0.
  • Usage: Enter the exact latitude of the target.
  • Integration: Must be used in conjunction with SIM_PLD_LON and SIM_PLD_HEIGHT.

SIM_PLD_LON

deg
Default 0
Range -180 180

Simulated Precision Landing Longitude (SIM_PLD_LON)

Description

SIM_PLD_LON defines the east/west coordinate of the landing target beacon used in the Precision Landing simulation.

This allows you to place the virtual beacon at a specific location on the map to test how the drone detects and navigates toward it from different approach angles.

Tuning & Behavior

  • Default: 0.
  • Usage: Enter the exact longitude of the target.
  • Integration: Must be used in conjunction with SIM_PLD_LAT and SIM_PLD_HEIGHT.

SIM_PLD_OPTIONS

Default 0
Range 0 1

Simulation Precision Landing Options (SIM_PLD_OPTIONS)

Description

SIM_PLD_OPTIONS allows developers to inject realistic faults into the simulated Precision Landing sensor.

  • Bit 0 (1): Enable Glitches. Randomly drops the target valid flag or shifts the target position momentarily to test the EKF's resilience to bad data.

Tuning & Behavior

  • Default: 0 (Perfect sensor).
  • Recommendation: Set to 1 when tuning your landing logic to ensure the drone doesn't make sudden, dangerous jerks if the sensor data becomes noisy.

SIM_PLD_ORIENT

Default 25
Range 0 38

Simulation Precision Landing Orientation (SIM_PLD_ORIENT)

Description

SIM_PLD_ORIENT tells the simulator which way the virtual camera is pointing.

By default, Precision Landing cameras (like IR-Lock) are mounted pointing straight down. However, some advanced setups use a gimballed camera or a fixed forward-facing camera for approach. This parameter allows you to test those configurations in SITL.

Tuning & Behavior

  • 25 (Default): Pitch 270 (Straight Down).
  • 0: None (Straight Forward).
  • Usage: Must match the PLND_ORIENT parameter in your vehicle's configuration to ensure the EKF correctly interprets the target's position relative to the drone.

SIM_PLD_RATE

Hz
Default 100
Range 0 200

Simulation Precision Landing Update Rate (SIM_PLD_RATE)

Description

SIM_PLD_RATE controls how many times per second the virtual Precision Landing sensor (e.g., IR-Lock or MAVLink beacon) sends data to the autopilot in SITL.

A higher rate provides smoother tracking during the final descent, while a lower rate can be used to simulate the latency or jitter of real-world sensors.

Tuning & Behavior

  • Default: 100 Hz.
  • Realistic Testing: If you are using a sensor known to be slow (e.g. some vision systems), try lowering this to 10 Hz or 20 Hz to see how the landing algorithm handles the increased lag.

SIM_PLD_SHIP

Default 0
Range 0 1

Simulation Landing Ship (SIM_PLD_SHIP)

Description

SIM_PLD_SHIP activates a moving landing platform.

This is the primary tool for testing Maritime operations. When enabled, SITL simulates a ship that pitches, rolls, and travels through the water. You can then test if your drone successfully performs a precision landing on a moving deck using the PLND_ENABLED logic.

SIM_PLD_TYPE

Default 0
Range 0 5

Simulated Precision Landing Type (SIM_PLD_TYPE)

Description

SIM_PLD_TYPE selects the protocol the virtual landing sensor uses.

  • 1: IR-Lock.
  • 3: MAVLink (for GCS-based landing targets).

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Use 1 (IR-Lock) for most autonomous landing tests.

SIM_PLD_YAW

deg
Default 0
Range -180 180

Simulation Precision Landing Target Yaw (SIM_PLD_YAW)

Description

SIM_PLD_YAW sets the heading of the virtual landing beacon or pad in SITL.

This is useful for testing sensors that report target orientation (like some 3D vision systems) or for verifying that the drone correctly aligns itself with the landing pad during the final touch-down phase.

Tuning & Behavior

  • Default: 0 (Pointing North).
  • Usage: Set to any heading from -180 to 180 degrees.

SIM_RATE_HZ

Hz
Default 1200
Range 50 2000

Simulation Loop Rate (SIM_RATE_HZ)

Description

SIM_RATE_HZ sets the "Frame Rate" of the physics world.

The flight controller runs its main loop at a certain speed (e.g. 400Hz for Copter, 50Hz for Plane). The simulator must run faster than the flight controller to provide smooth sensor data.

  • 1200 (Default): Good for most multirotors.
  • 400: Sufficient for Plane or Rover.

Tuning & Behavior

  • Constraint: Must be a multiple of the flight controller loop rate to avoid aliasing artifacts.

SIM_RC_CHANCOUNT

Default 16
Range 1 32

Simulated RC Channel Count (SIM_RC_CHANCOUNT)

Description

SIM_RC_CHANCOUNT sets the capacity of the virtual radio receiver.

Tuning & Behavior

  • Default Value: 16.
  • Recommendation: Keep at 16 for most standard setups. Use higher values (up to 32) for testing complex Lua scripts or multi-gimbal setups.

SIM_RC_FAIL

Default 0
Range 0 2

Simulated RC Failure (SIM_RC_FAIL)

Description

SIM_RC_FAIL simulates your radio receiver losing power or signal.

  • 0: Normal. RC signal is healthy.
  • 1: No Pulses. The simulator stops sending any RC data to the autopilot. Mimics a disconnected SBus cable.
  • 2: Failsafe Values. Channels stay at neutral, except throttle which drops to 950µs.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Use this in flight to verify that your FS_THR_ENABLE or RC_FS_ACTION is working correctly.

SIM_RFL_OPTS

Default 1
Range 0 7

Simulation RealFlight Options (SIM_RFL_OPTS)

Description

SIM_RFL_OPTS provides advanced control over the communication between ArduPilot SITL and the RealFlight simulator (FlightAxis).

  • Bit 0 (1): Reset Position. If enabled, ArduPilot will command RealFlight to reset the aircraft position to the runway whenever the SITL instance is rebooted or reset.
  • Bit 1 (2): Use MAVLink State.

Tuning & Behavior

  • Default: 1 (Reset Position enabled).
  • Note: This is only relevant if you are using ArduPilot SITL in "RealFlight mode" (e.g. running sim_vehicle.py -v ArduPlane -f realflight).

SIM_RICH_CTRL

Default -1
Range -1 16

SIM_RICH_CTRL: RichenPower Control Pin

Description

Pin RichenPower is connected to.

Values

  • Range: -1 to 16
  • Default: -1 (Disabled)

Description

This parameter configures the SITL (Simulator) to emulate a RichenPower Hybrid Generator.

  • Function: It specifies the Sim-Pin used to simulate the control signal sent to the generator.
  • Usage: Set to 8 (simulated UART or PWM pin) to enable the generator simulation logic, allowing you to test the generator drivers and failsafes without hardware.

SIM_RICH_ENABLE

Default 0
Range 0 1

Simulated Rich Environment Enable (SIM_RICH_ENABLE)

Description

SIM_RICH_ENABLE turns on the "Chaos Monkey."

It enables a suite of randomized sensor glitches, timing jitters, and environmental disturbances designed to stress-test the autopilot's failsafe logic. It is primarily used by developers to find bugs in error handling code.

Tuning & Behavior

  • 0: Disabled.
  • 1: Enabled.

SIM_SAIL_TYPE

Default 0
Range 0 5

Simulation Sailboat Type (SIM_SAIL_TYPE)

Description

SIM_SAIL_TYPE tells the physics engine which kind of wind-powered boat to simulate.

  • 0: Mono-hull. Standard sailboat.
  • 1: Catamaran.
  • 2: Wingsail. High-efficiency rigid sail.

SIM_SB_ALT_TARG

m
Default 1000
Range 0 40000

Simulated StratoBlimp Target Altitude (SIM_SB_ALT_TARG)

Description

SIM_SB_ALT_TARG sets the "Zero Buoyancy" height for the StratoBlimp simulation. At this altitude, the blimp will naturally float without using its motors.

Tuning & Behavior

  • Default Value: 1000 m.

SIM_SB_ARM_LEN

m
Default 3.6
Range 0 100

Simulation Blimp Arm Length (SIM_SB_ARM_LEN)

Description

SIM_SB_ARM_LEN defines the physical geometry of the simulated StratoBlimp.

It sets the length of the lever arm between the blimp's center of mass and its propulsion units. This distance determines how much torque is generated by the motors, directly affecting the blimp's turning rate (Yaw) and its ability to pitch.

Tuning & Behavior

  • Default: 3.6 meters.
  • Physics: A longer arm increases the rotational inertia but also increases the control authority (leverage).
  • Usage: Match this to the physical dimensions of your blimp design for an accurate simulation.

SIM_SB_CLMB_RT

m/s
Default 5
Range 0 50

Simulation Blimp Target Climb Rate (SIM_SB_CLMB_RT)

Description

SIM_SB_CLMB_RT defines the vertical speed the simulated StratoBlimp attempts to maintain while climbing toward its target altitude.

This parameter simulates the buoyancy-to-drag balance of the blimp's envelope. A higher value means the blimp has more lift or less aerodynamic drag in the vertical axis.

Tuning & Behavior

  • Default: 5 m/s.
  • Physics: This value is used by the simulator's simplified physics model to calculate the vertical force needed to achieve the target rate.

SIM_SB_COL

m
Default 2.54
Range 0 10

Simulation Blimp Center of Lift (SIM_SB_COL)

Description

SIM_SB_COL defines the physical offset between the buoyant center of the blimp's envelope (where it is pulled UP) and its center of gravity (where it is pulled DOWN).

In a stable blimp, the center of lift is usually high above the center of gravity (the gondola). This distance creates a "Pendulum Effect" that naturally keeps the blimp level. Increasing this value makes the blimp more stable but slower to pitch.

Tuning & Behavior

  • Default: 2.54 meters.
  • Physics: A larger offset results in a stronger restoring torque when the blimp is tilted.
  • Warning: Setting this to 0 will make the blimp neutrally stable in pitch/roll, meaning it will stay at whatever angle it is pushed to.

SIM_SB_DRAG_FWD

Default 0.27
Range 0 5.0

Simulation Blimp Forward Drag (SIM_SB_DRAG_FWD)

Description

SIM_SB_DRAG_FWD defines how "Slippery" the blimp is when flying straight ahead.

A lower value means the blimp is more streamlined and will reach a higher top speed for a given motor thrust. A higher value simulates a blunter shape or more surface friction.

Tuning & Behavior

  • Default: 0.27.
  • Physics: Drag force is calculated as $F\_d = \frac{1}{2} \rho v^2 C\_d A$. This parameter represents the combined $C\_d A$ term (Coefficient of Drag $\times$ Frontal Area) for the forward direction.

SIM_SB_DRAG_SIDE

Default 0.5
Range 0 5.0

Simulation Blimp Lateral Drag (SIM_SB_DRAG_SIDE)

Description

SIM_SB_DRAG_SIDE simulates the air resistance the blimp encounters when moving sideways or drifting.

Because blimps are long and cigar-shaped, their side profile (Lateral Area) is much larger than their front profile. This means the drag from the side should be significantly higher than the forward drag. This parameter is critical for modeling how the blimp handles crosswinds.

Tuning & Behavior

  • Default: 0.5.
  • Physics: This value is typically 2x to 5x higher than SIM_SB_DRAG_FWD.
  • Effect: If this value is too low, the simulated blimp will "slide" sideways too easily in turns.

SIM_SB_DRAG_UP

Default 0.4
Range 0 5.0

Simulation Blimp Vertical Drag (SIM_SB_DRAG_UP)

Description

SIM_SB_DRAG_UP simulates the air resistance the blimp encounters when climbing or descending.

Because of the large horizontal surface area of a blimp's envelope (top and bottom), vertical drag is substantial. This parameter determines the terminal velocity for ascent (due to buoyancy) and descent.

Tuning & Behavior

  • Default: 0.4.
  • Physics: This value balances against SIM_SB_FLR (Free Lift Rate). A higher drag coefficient means the blimp will ascend slower for the same amount of positive buoyancy.

SIM_SB_FLR

Default 0.12
Range 0 1.0

Simulation Blimp Free Lift Rate (SIM_SB_FLR)

Description

SIM_SB_FLR simulates the "Positive Buoyancy Bias" often used in stratospheric balloon missions.

Many high-altitude airships are designed to be slightly lighter than air so they naturally ascend without using motor power. This parameter defines how much extra lift is available.

  • 0.0: Perfectly neutrally buoyant (will float at current altitude).
  • 0.12 (Default): 12% excess lift. The blimp will ascend automatically.

Tuning & Behavior

  • Default: 0.12.
  • Physics: This excess lift must be counteracted by downward thrust from the motors if the blimp needs to hold altitude or descend.

SIM_SB_HMASS

kg
Default 13.54
Range 0 1000

Simulation Blimp Helium Mass (SIM_SB_HMASS)

Description

SIM_SB_HMASS simulates the weight of the lifting gas itself.

While helium is lighter than air, it still has mass. This parameter, combined with the envelope volume (implicit in the simulation's buoyancy logic), allows the physics engine to calculate the net lift and inertia of the airship.

Tuning & Behavior

  • Default: 13.54 kg.
  • Physics: A larger mass of helium implies a larger envelope volume, which increases both lift and aerodynamic drag.

SIM_SB_MASS

kg
Default 80
Range 1 500

Simulation Blimp Mass (SIM_SB_MASS)

Description

SIM_SB_MASS defines the weight of the virtual blimp used in the StratoBlimp simulation.

This parameter directly affects the physics engine, influencing how much buoyancy (Helium) is needed to stay airborne and how the blimp reacts to motor thrust and wind.

SIM_SB_MOI_PITCH

kg*m^2
Default 3050
Range 100 10000

Simulation Blimp Pitch Inertia (SIM_SB_MOI_PITCH)

Description

SIM_SB_MOI_PITCH defines how hard it is to tilt the blimp's nose up or down.

Because blimps are very long, their mass is distributed far from the center of rotation. This results in a very high pitch inertia. This parameter simulates that "heavy" feel, meaning it takes significant thrust to start pitching the nose up, and equally significant thrust to stop it once it's moving.

Tuning & Behavior

  • Default: 3050 $kg \cdot m^2$.
  • Physics: This value is typically much higher than the Roll Inertia (SIM_SB_MOI_ROLL) due to the elongated shape of the hull.
  • Effect: If this value is too low, the simulated blimp will be able to perform impossible aerobatic loops.

SIM_SB_MOI_ROLL

kg*m^2
Default 1400
Range 100 10000

Simulation Blimp Roll Inertia (SIM_SB_MOI_ROLL)

Description

SIM_SB_MOI_ROLL defines how hard it is to tilt the blimp side-to-side.

A blimp with a high roll inertia is very stable and resists being rocked by turbulence, but it takes a lot of force to bank into a turn. A low roll inertia makes the blimp feel "twitchy" and unstable.

Tuning & Behavior

  • Default: 1400 $kg \cdot m^2$.
  • Physics: This value is derived from the mass distribution of the envelope and gondola. Since most of the mass is concentrated low (in the gondola), the roll inertia is typically lower than the pitch or yaw inertia.

SIM_SB_MOI_YAW

kg*m^2
Default 2800
Range 100 10000

Simulation Blimp Yaw Inertia (SIM_SB_MOI_YAW)

Description

SIM_SB_MOI_YAW defines how hard it is to turn the blimp left or right.

Like pitch inertia, yaw inertia is high for blimps because of their length. This parameter simulates the "resistance to turning" that pilot's feel. A high value means the blimp will be slow to start turning, but will also coast through the turn and be slow to stop spinning once the motors are centered.

Tuning & Behavior

  • Default: 2800 $kg \cdot m^2$.
  • Physics: This value dictates the responsiveness of the heading control loop.
  • Effect: If this value is too high, the blimp will feel "sluggish" and may overshoot its target heading. If too low, it will turn unrealistically fast.

SIM_SB_MOT_ANG

deg
Default 20
Range 0 90

Simulation Blimp Max Motor Angle (SIM_SB_MOT_ANG)

Description

SIM_SB_MOT_ANG defines the range of motion for the vectored thrust motors on the simulated StratoBlimp.

Unlike a standard drone, many blimps use motors that can tilt up or down to provide vertical lift or horizontal thrust. This parameter sets the maximum mechanical tilt angle that the simulator will model.

Tuning & Behavior

  • Default: 20 degrees.
  • Usage: Set this to match the physical tilt range of your blimp's motor mounts.
  • Physics: This determines how much of the motor's thrust can be directed vertically for altitude control versus horizontally for forward speed.

SIM_SB_MOT_THST

N
Default 145
Range 0 1000

Simulation Blimp Max Motor Thrust (SIM_SB_MOT_THST)

Description

SIM_SB_MOT_THST defines the "Power" of the simulated propulsion system.

It represents the raw force (in Newtons) that a single motor/propeller unit generates when running at full throttle. This determines the blimp's maximum speed and its ability to fight against simulated wind.

Tuning & Behavior

  • Default: 145 N.
  • Conversion: 1 Newton $\approx$ 102 grams of thrust.
  • Usage: Measure or calculate the peak thrust of your real motors and enter the equivalent Newtons here.

SIM_SB_WVANE

m
Default 0.3
Range -10 10

Simulation Blimp Weathervane Offset (SIM_SB_WVANE)

Description

SIM_SB_WVANE determines how strongly the StratoBlimp naturally points into the wind.

It represents the horizontal distance between the Center of Gravity (CoG) and the Center of Pressure (CoP) for side winds.

  • Positive Value: Center of Drag is behind the Center of Mass. The blimp is stable and will naturally turn its nose into the wind (like a weather vane).
  • Negative Value: Center of Drag is in front of the Center of Mass. The blimp is unstable and will try to fly tail-first.

Tuning & Behavior

  • Default: 0.3 meters.
  • Physics: A larger positive value means stronger directional stability but makes it harder for the motors to turn the blimp out of the wind.

SIM_SB_YAW_RT

deg/s
Default 60
Range 0 360

Simulation Blimp Max Yaw Rate (SIM_SB_YAW_RT)

Description

SIM_SB_YAW_RT sets the "Turning Speed" limit for the simulated StratoBlimp.

It defines how many degrees per second the blimp will rotate when the motor outputs are fully differential (full left/right stick). This allows developers to simulate the sluggish turning characteristics of large blimps or the highly maneuverable response of small electric airships.

Tuning & Behavior

  • Default: 60 $deg/s$.
  • Physics: This parameter determines the effective yaw torque produced by the motors in the simulator's physics model.

SIM_SERVO_DELAY

s
Default 0
Range 0 0.1

Simulated Servo Delay (SIM_SERVO_DELAY)

Description

SIM_SERVO_DELAY simulates the processing lag of digital servos or PWM signal propagation.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 0.05 (50ms). You will likely see the drone start to wobble as the control loop becomes unstable due to the lag.

SIM_SERVO_FILTER

Hz
Default 0
Range 0 100

Simulation Servo Filter (SIM_SERVO_FILTER)

Description

SIM_SERVO_FILTER adds damping to the simulated control surfaces.

Real servos and mechanical linkages don't snap to a new position instantly; they have physical inertia. This parameter simulates that "Smoothness" by applying a frequency-based filter to the output.

  • 0: Disabled.
  • Value (Hz): The cutoff frequency. Lower values make the servos move slower and "mushier."

Tuning & Behavior

  • Default: 0.
  • Usage: Set to 20 or 30 to simulate a typical high-quality servo.
  • Integration: Works in combination with SIM_SERVO_SPEED.

SIM_SERVO_SPEED

s/60deg
Default 0.11
Range 0.01 1.0

Simulated Servo Speed (SIM_SERVO_SPEED)

Description

SIM_SERVO_SPEED defines how fast the virtual servos move.

Real servos aren't instant. If you have a slow servo on a racing quad, the PID loop will oscillate because the motor doesn't reach the target speed fast enough. This parameter allows you to simulate that physical delay.

Tuning & Behavior

  • Default Value: 0.11 s/60° (Standard hobby servo).
  • High Performance: Set to 0.05 for fast brushless servos.
  • Large Drones: Set to 0.20 for heavy-duty, slow servos.

SIM_SF_JS_AXIS1

Default 0
Range 0 7

Simulation SFML Joystick Axis 1 (SIM_SF_JS_AXIS1)

Description

SIM_SF_JS_AXIS1 (and AXIS2 through AXIS8) allows you to rebind the physical axes of your controller to the expected inputs in the simulator.

By default, Axis 1 is typically mapped to the X-axis (Roll/Aileron) of the joystick.

Tuning & Behavior

  • Axis Mapping: The value corresponds to the SFML sf::Joystick::Axis enum (X, Y, Z, R, U, V, PovX, PovY).
  • Configuration: If your controls are swapped (e.g. throttle is on the wrong stick), use these parameters to realign them.
Default sf::Joystick::Axis::Y
Range null

Note: This parameter functions identically to SIM_SF_JS_AXIS1.

Default sf::Joystick::Axis::Z
Range null

Note: This parameter functions identically to SIM_SF_JS_AXIS1.

Default sf::Joystick::Axis::U
Range null

Note: This parameter functions identically to SIM_SF_JS_AXIS1.

Default sf::Joystick::Axis::V
Range null

Note: This parameter functions identically to SIM_SF_JS_AXIS1.

Default sf::Joystick::Axis::R
Range null

Note: This parameter functions identically to SIM_SF_JS_AXIS1.

Default sf::Joystick::Axis::PovX
Range null

Note: This parameter functions identically to SIM_SF_JS_AXIS1.

Default sf::Joystick::Axis::PovY
Range null

Note: This parameter functions identically to SIM_SF_JS_AXIS1.

SIM_SF_JS_STICK

Default 0
Range 0 7

Simulation SFML Joystick Index (SIM_SF_JS_STICK)

Description

SIM_SF_JS_STICK selects which physical joystick or gamepad connected to your computer is used to control the simulated vehicle in SITL.

This is used by the SFML (Simple and Fast Multimedia Library) backend of SITL. If you have multiple controllers connected, you may need to change this ID to select the correct one.

Tuning & Behavior

  • Default: 0.
  • Usage: Set to 0 for the first detected controller, 1 for the second, and so on.

SIM_SHIP_DSIZE

m
Default 10
Range 1 100

Simulated Ship Deck Size (SIM_SHIP_DSIZE)

Description

SIM_SHIP_DSIZE defines the dimensions of the helipad.

This affects the visual model and the collision detection. If the drone lands outside this area, it will fall into the "Water."

Tuning & Behavior

  • Default Value: 10 m.

SIM_SHIP_ENABLE

Default 0
Range 0 1

Simulated Ship Enable (SIM_SHIP_ENABLE)

Description

SIM_SHIP_ENABLE places a large, moving ship in the simulation.

This is primarily used for testing "Ship Landing" logic. The ship has a helipad deck and moves along a pre-defined path or at a constant velocity.

Tuning & Behavior

  • 0: Disabled.
  • 1: Enabled.

SIM_SHIP_OFS

m
Default 0

Simulation Ship Position Offset (SIM_SHIP_OFS)

Description

SIM_SHIP_OFS allows you to move the simulated ship's starting point.

When simulating a moving platform (like a ship or truck), it is useful to be able to place it at a specific distance from the drone's "Home" or takeoff location.

  • Format: A vector (X, Y, Z) in meters.
  • X: North.
  • Y: East.
  • Z: Altitude (Negative is down/below home).

Tuning & Behavior

  • Default: 0,0,0.
  • Usage: Set Z to a positive value (e.g. 5m) to simulate the ship's deck being higher than the water level or ground level.

SIM_SHIP_PSIZE

m
Default 5
Range 1 50

Simulated Ship Pad Size (SIM_SHIP_PSIZE)

Description

SIM_SHIP_PSIZE controls the visual "H" or circle on the deck.

SIM_SHIP_SPEED

m/s
Default 0
Range 0 15

Simulated Ship Speed (SIM_SHIP_SPEED)

Description

SIM_SHIP_SPEED sets how fast the target vessel moves.

Tuning & Behavior

  • Default Value: 0 m/s.
  • Recommendation: Set to 5-10 m/s to test the drone's ability to track and land on a moving deck.

SIM_SHIP_SYSID

Default 0
Range 0 255

Simulated Ship System ID (SIM_SHIP_SYSID)

Description

SIM_SHIP_SYSID gives the ship a "Voice."

If set to a non-zero value (e.g. 20), the ship will broadcast its position via MAVLink GLOBAL_POSITION_INT messages on the simulated network. This allows the drone to track the ship as a dynamic "Follow Me" target or a moving home point.

Tuning & Behavior

  • Default Value: 0 (Silent).

SIM_SHOVE_TIME

ms
Default 0
Range 0 10000

Simulated Shove Time (SIM_SHOVE_TIME)

Description

SIM_SHOVE_TIME determines if the "Shove" is a punch or a push.

If set to 0, the velocity change is instantaneous (impulse). If set to a value (e.g. 2000 ms), the force is applied over that duration, simulating a sustained wind gust or thruster firing.

Tuning & Behavior

  • Default Value: 0.

SIM_SHOVE_X

m/s
Default 0
Range -30 30

Simulated Shove X (SIM_SHOVE_X)

Description

SIM_SHOVE_X kicks the drone forward or backward.

When you change this parameter (e.g. via MAVProxy), the simulator instantly adds this velocity to the vehicle's state. It is used to test the position controller's ability to recover from a sudden disturbance.

Tuning & Behavior

  • Default Value: 0.
  • Usage: Set to 5 to simulate being hit by a 5 m/s gust or object from behind.

SIM_SHOVE_Y

$m/s^2$
Default 0
Range -100 100

Simulation Shove Y (SIM_SHOVE_Y)

Description

SIM_SHOVE_Y hits the drone from the side.

Unlike SIM_WIND, which is an aerodynamic force, SHOVE is a direct acceleration/force applied to the body.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 10 for 1 second, then back to 0. This tests the drone's ability to recover from a hard collision or extreme gust.

SIM_SHOVE_Z

$m/s^2$
Default 0
Range -100 100

Simulation Shove Z (SIM_SHOVE_Z)

Description

SIM_SHOVE_Z simulates a sudden vertical impact or force.

  • Positive Value: Pushes the drone Down.
  • Negative Value: Pushes the drone Up.

Tuning & Behavior

  • Testing: Set to 20 for a fraction of a second to simulate a heavy object being dropped on the drone or a sudden downburst. Test the position controller's ability to recover the target altitude.

SIM_SLUP_DRAG

Default 1.0
Range 0 10

Slung Payload Drag Coefficient (SIM_SLUP_DRAG)

Description

SIM_SLUP_DRAG determines how "Aerodynamic" the payload is.

A high drag coefficient (e.g. 5.0) simulates a bulky object (like a large box) that will be pushed backward by the wind as the drone flies forward. A low value (e.g. 0.1) simulates a streamlined weight that hangs mostly vertical even at high speeds.

Tuning & Behavior

  • Default Value: 1.0.

SIM_SLUP_ENABLE

Default 0
Range 0 1

Slung Payload Sim Enable (SIM_SLUP_ENABLE)

Description

SIM_SLUP_ENABLE adds a swinging physical weight beneath the drone.

This is used for testing helicopter or multirotor "Slung Load" operations. The simulator calculates the pendulum physics, including the mass of the payload, the length of the line, and the drag on the object. The swinging payload exerts forces back on the drone, which can cause significant instability if not tuned correctly.

Tuning & Behavior

  • 0: Disabled.
  • 1: Enabled.
  • Physics: The payload is modeled as a point mass on a tether. It uses the vehicle's Earth-frame position and velocity to calculate tension and centripetal forces.

SIM_SLUP_LINELEN

m
Default 30.0
Range 1 100

Slung Payload Line Length (SIM_SLUP_LINELEN)

Description

SIM_SLUP_LINELEN sets the distance between the drone and the payload.

Tuning & Behavior

  • Default Value: 30 m.
  • Effect: Longer lines result in slower pendulum oscillations but can lead to very large displacements. Shorter lines react much more quickly and can impart sharp "Jerk" forces to the flight controller.

SIM_SLUP_SYSID

Default 2
Range 0 255

Slung Payload MAVLink System ID (SIM_SLUP_SYSID)

Description

SIM_SLUP_SYSID enables the slung payload to report its own position to the GCS.

When enabled, the simulator spawns a second MAVLink "Vehicle" at the payload's location. This allows you to see the payload swinging on your GCS map or in a 3D visualizer (like Mission Planner's HUD).

Tuning & Behavior

  • Default Value: 2.
  • Note: The payload broadcasts heartbeats as a MAV_TYPE_AIRSHIP with component ID MAV_COMP_ID_USER11.

SIM_SLUP_WEIGHT

kg
Default 1.0
Range 0 15

Slung Payload Weight (SIM_SLUP_WEIGHT)

Description

SIM_SLUP_WEIGHT sets the mass of the underslung object.

Tuning & Behavior

  • Default Value: 1.0 kg.
  • Effect: Increasing the weight increases the "Pendulum Effect." A heavy payload can pull the drone into a state where it can no longer maintain attitude or altitude if it starts swinging excessively.

SIM_SONAR_GLITCH

m
Default 0
Range -5 5

Simulation Sonar Glitch (SIM_SONAR_GLITCH)

Description

SIM_SONAR_GLITCH simulates a "bad bounce" or sensor error.

Rangefinders often report incorrect distances when flying over grass or water. This parameter allows you to inject sudden jumps in the reported altitude to test the EKF's rejection logic or the terrain following safety limits.

SIM_SONAR_POS

m
Default 0
Range 0 5

Simulation Sonar Position (SIM_SONAR_POS)

Description

SIM_SONAR_POS defines the mounting location of the simulated rangefinder. Useful for testing terrain following and precise landing algorithms.

SIM_SONAR_RND

m
Default 0
Range 0 5

Simulated Sonar Noise (SIM_SONAR_RND)

Description

SIM_SONAR_RND adds Gaussian noise to the rangefinder distance.

Tuning & Behavior

  • Default Value: 0 m.
  • Recommendation: Set to 0.05 (5cm) for realistic testing.

SIM_SONAR_ROT

Default 0
Range 0 35

Simulation Sonar Rotation (SIM_SONAR_ROT)

Description

SIM_SONAR_ROT sets the direction the simulated rangefinder is pointing.

  • 25: Down (Standard for altimeters).
  • 0: Forward (Standard for obstacle avoidance).

SIM_SONAR_SCALE

m/V
Default 12.1212
Range 0 100

Simulated Sonar Scale (SIM_SONAR_SCALE)

Description

SIM_SONAR_SCALE simulates the calibration of an analog rangefinder (like the Maxbotix EZ series).

It defines how many meters of distance are represented by 1 Volt of output.

Tuning & Behavior

  • Default Value: 12.1212 (Standard Maxbotix).
  • Testing: Change this to simulate an uncalibrated sensor and verify your RNGFND1_SCALING parameter can correct it.

SIM_SPEEDUP

Default -1
Range -1 100

Simulation Speedup (SIM_SPEEDUP)

Description

SIM_SPEEDUP allows you to run the simulation faster than real-time.

  • 1: Real-time (1 second = 1 second).
  • 10: 10x speed. Useful for flying long missions quickly.
  • -1 (Default): Run as fast as the computer CPU allows.

Tuning & Behavior

  • Default Value: -1.
  • Note: If your computer is slow, the simulation might run slower than real-time even if you set this to 10.

SIM_SPR_ENABLE

Default 0
Range 0 1

Simulated Sprayer Enable (SIM_SPR_ENABLE)

Description

SIM_SPR_ENABLE adds a liquid tank to the drone.

When the sprayer is active, the simulator slowly decreases the total mass of the drone, mimicking the fluid being pumped out. This allows you to test if your tuning holds up as the payload weight changes.

Tuning & Behavior

  • 0: Disabled.
  • 1: Enabled.

SIM_SPR_PUMP

L/s
Default 0
Range 0 10

Simulated Sprayer Pump Rate (SIM_SPR_PUMP)

Description

SIM_SPR_PUMP sets how fast the tank empties.

Tuning & Behavior

  • Default Value: 0.

SIM_SPR_SPIN

Nm
Default 0
Range 0 1

Simulated Sprayer Spinner Torque (SIM_SPR_SPIN)

Description

SIM_SPR_SPIN simulates the reaction torque from a spinning atomizer disk.

Some crop sprayers use high-speed spinning disks to atomize the liquid. These act like small gyroscopes and can impart a yaw torque on the drone. This parameter helps verify that the yaw controller can handle the disturbance.

Tuning & Behavior

  • Default Value: 0.

SIM_TA_ENABLE

Default 0
Range 0 1

Simulated ToneAlarm Enable (SIM_TA_ENABLE)

Description

SIM_TA_ENABLE activates the simulated hardware buzzer.

In a real flight controller, the ToneAlarm is the speaker that plays the "Happy" arming tune, "Sad" battery low tones, and error chirps. Enabling this in SITL allows developers to hear these tones while testing in the simulator.

The Engineer's View

Defined in SIM_ToneAlarm.cpp.
When enabled, the SITL backend pipes the audio frequency commands to the host computer's audio system (or logs them for verification). It mimics the behavior of the AP_Notify ToneAlarm backend.

Tuning & Behavior

  • Default Value: 0 (Silent).
  • 1: Tones are enabled.

SIM_TEMP_BFACTOR

Default 0.0
Range 0 5

Simulation Barometer Temperature Factor (SIM_TEMP_BFACTOR)

Description

SIM_TEMP_BFACTOR simulates "Thermal Altitude Drift."

Real pressure sensors (barometers) are slightly affected by temperature. As the flight controller heats up, the reported altitude might "drift" by a few meters even if the drone is sitting still. This parameter simulates that error.

Tuning & Behavior

  • Default Value: 0 (Perfect sensor).
  • Testing: Set to 1.2 to simulate a typical ICM-20789 sensor.

SIM_TEMP_BRD_OFF

degC
Default 20
Range 0 50

Simulation Board Temperature Offset (SIM_TEMP_BRD_OFF)

Description

SIM_TEMP_BRD_OFF simulates the self-heating of the flight controller electronics.

In the real world, the inside of an autopilot case is hotter than the outside air due to the heat generated by the CPU and power regulators. This parameter adds a fixed offset to the simulated ambient temperature to create the "Board Temperature" sensor reading.

Tuning & Behavior

  • Default: 20 °C. (If ambient is 25°C, the board reports 45°C).
  • Usage: Useful for testing temperature calibration routines (TCAL) or verifying fan control logic without needing a heat gun.

SIM_TEMP_START

degC
Default 25.0
Range -20 60

Simulation Start Temperature (SIM_TEMP_START)

Description

SIM_TEMP_START sets the initial temperature for SITL sensor thermal models.

ArduPilot simulates "Thermal Warmup." When the simulation starts, the sensors (IMU, Baro) begin at this temperature and gradually heat up towards the internal operating temperature of the flight controller. This is used to test temperature compensation algorithms.

Tuning & Behavior

  • Default Value: 25.0°C.
  • Testing: Set to 0.0 to test how your drone handles a cold-start in winter conditions.

SIM_TEMP_TCONST

s
Default 30.0
Range 1 1000

Simulation Temperature Time Constant (SIM_TEMP_TCONST)

Description

SIM_TEMP_TCONST defines how fast the flight controller heats up in the simulator.

A lower value means the board reaches its operating temperature very quickly. A higher value simulates a large, heavy flight controller that takes a long time to stabilize.

SIM_TERRAIN

Default 1
Range 0 1

Simulation Terrain Enable (SIM_TERRAIN)

Description

SIM_TERRAIN turns on the "Ground."

When enabled, SITL downloads SRTM terrain data (just like the real flight controller) and uses it to calculate the ground height at the drone's current location. This is essential for testing terrain following, rangefinder altimetry, and crash detection.

  • 0: Disabled. The world is flat at altitude 0.
  • 1: Enabled. The ground height varies.

SIM_TETH_ENABLE

Default 0
Range 0 1

Simulated Tether Enable (SIM_TETH_ENABLE)

Description

SIM_TETH_ENABLE simulates a physical cable attached to the drone.

This is used for testing tethered power systems. The simulator calculates the weight and drag of the cable as the drone flies higher, pulling it down and affecting its stability.

Tuning & Behavior

  • 0: Disabled.
  • 1: Enabled.

SIM_TETH_LINELEN

m
Default 100
Range 10 1000

Simulated Tether Length (SIM_TETH_LINELEN)

Description

SIM_TETH_LINELEN sets the maximum reach of the cable.

If the drone flies further than this distance from the tether anchor point, it will be physically jerked back by the "Rope," potentially causing a crash or oscillation.

Tuning & Behavior

  • Default Value: 100 m.

SIM_TETH_SYSID

Default 0
Range 0 255

Simulated Tether System ID (SIM_TETH_SYSID)

Description

SIM_TETH_SYSID allows the simulator to spoof messages from a "Smart Tether."

Real tether stations often report cable tension and power usage via MAVLink. This parameter sets the source ID for those simulated messages.

Tuning & Behavior

  • Default Value: 0 (Disabled).

SIM_THML_SCENARI

Default 0
Range 0 5

Simulation Thermal Scenarios (SIM_THML_SCENARI)

Description

SIM_THML_SCENARI defines the "Thermal Map" for autonomous glider testing.

Instead of just one random thermal, this parameter selects different distributions of rising air. Useful for verifying that ArduSoar can reliably find and track lift in varied atmospheric conditions.

SIM_TIDE_DIR

deg
Default 0
Range 0 360

Simulated Tide Direction (SIM_TIDE_DIR)

Description

SIM_TIDE_DIR sets the compass bearing of the water current.

  • 0: North current (pushing the boat towards South).
  • 180: South current.

SIM_TIDE_SPEED

m/s
Default 0
Range 0 5

Simulated Tide Speed (SIM_TIDE_SPEED)

Description

SIM_TIDE_SPEED simulates the "Wind of the Water."

For ArduRover (Boats) and ArduSub, this parameter adds a constant water current that pushes the vehicle in a specific direction. This is the primary way to test "Position Hold" and navigation robustness against currents.

Tuning & Behavior

  • Default Value: 0 m/s.

SIM_TIME_JITTER

us
Default 0
Range 0 10000

Simulated Time Jitter (SIM_TIME_JITTER)

Description

SIM_TIME_JITTER adds "Instability" to the simulator's clock.

On a real flight controller, the main loop usually runs at exactly 400Hz or 1000Hz. However, CPU spikes can cause small delays. This parameter allows you to simulate that behavior in SITL to ensure the EKF and PID controllers don't crash or lose stability when the timing isn't perfect.

SIM_TWIST_TIME

ms
Default 0
Range 0 10000

Simulated Twist Time (SIM_TWIST_TIME)

Description

SIM_TWIST_TIME controls the duration of the rotational disturbance.

Tuning & Behavior

  • Default Value: 0.

SIM_TWIST_X

deg/s
Default 0
Range -360 360

Simulated Twist X (SIM_TWIST_X)

Description

SIM_TWIST_X spins the drone in Roll.

Use this to test the attitude controller's ability to stop a roll tumble.

Tuning & Behavior

  • Default Value: 0.

SIM_TWIST_Y

$deg/s^2$
Default 0
Range -100 100

Simulation Twist Y (SIM_TWIST_Y)

Description

SIM_TWIST_Y applies an external rotation force to the pitch axis.

This is useful for simulating a mechanical failure (like a loose motor mount) or an external snag (like a payload cable pulling on the frame). It tests the attitude controller's ability to maintain level flight under constant torque.

SIM_TWIST_Z

$deg/s^2$
Default 0
Range -100 100

Simulation Twist Z (SIM_TWIST_Z)

Description

SIM_TWIST_Z applies an external rotation force to the yaw axis.

Use this to simulate a "Broken Propeller" scenario where one motor is producing more torque than the others, forcing the drone to spin.

SIM_UART_LOSS

%
Default 0
Range 0 100

Simulated UART Data Loss (SIM_UART_LOSS)

Description

SIM_UART_LOSS simulates a "Bad Connection" or noisy telemetry link.

It randomly drops the specified percentage of serial bytes. This is perfect for testing how well your GCS handles packet loss or how resilient your Serial GPS driver is to data corruption.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 5% or 10% and observe if your MAVLink connection remains stable.

SIM_VIB_FREQ

Hz
Default 0
Range 0 300

Simulation Vibration Frequency (SIM_VIB_FREQ)

Description

SIM_VIB_FREQ adds realistic motor noise to the IMU.

  • 0: No vibration.
  • 50-200: Typical motor/propeller frequencies.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Essential for testing Harmonic Notch Filters. Set SIM_VIB_FREQ to 80Hz, enable INS_HNTCH_ENABLE, and see if the FFT or Notch filters successfully remove it from the logs.

SIM_VIB_MOT_HMNC

Default 1
Range 1 5

Simulated Motor Harmonics (SIM_VIB_MOT_HMNC)

Description

SIM_VIB_MOT_HMNC simulates the "Overtones" of motor vibration.

In the real world, a motor doesn't just vibrate at its base frequency; it also creates noise at 2x, 3x, and 4x that frequency. This parameter tells SITL how many of these harmonics to simulate, allowing you to test if your INS_HNTCH_HMNCS bitmask is set correctly.

Tuning & Behavior

  • Default Value: 1.
  • Testing: Set to 3 and verify your Harmonic Notch can clear all three spikes in an FFT graph.

SIM_VIB_MOT_MASK

Default 0
Range 0 4294967295

Simulated Motor Vibration Mask (SIM_VIB_MOT_MASK)

Description

SIM_VIB_MOT_MASK selects which virtual motors are "Noisy."

By default (0), all motors contribute equally to vibration. By setting this bitmask, you can simulate a single motor with a damaged propeller to see how the EKF handles asymmetrical noise.

Tuning & Behavior

  • Default Value: 0 (All motors).
  • Bit 0 (1): Motor 1 only.

SIM_VIB_MOT_MAX

Hz
Default 0
Range 0 500

Simulated Motor Vibration Max Frequency (SIM_VIB_MOT_MAX)

Description

SIM_VIB_MOT_MAX sets the upper bound of the vibration "Whine."

Real motors vibrate at different frequencies as they spin up. This parameter allows you to test your Harmonic Notch Filter (INS_HNTCH_ENABLE) by injecting a realistic vibration spike that moves between 0 and this maximum frequency.

Tuning & Behavior

  • Default Value: 0 (Disabled).
  • Recommendation: Set to 150 or 200 Hz to test your notch filter's tracking ability.

SIM_VIB_MOT_MULT

Default 1.0
Range 0 10

Simulation Vibration Motor Scale (SIM_VIB_MOT_MULT)

Description

SIM_VIB_MOT_MULT controls the "Volume" of the simulated motor vibration.

While SIM_VIB_FREQ sets the frequency of the noise, this parameter determines how strong those vibrations are. This is used to test the resilience of the EKF and the effectiveness of internal dampening filters.

  • 1.0 (Default): Standard vibration level.
  • 5.0: Extreme vibration. Good for testing "Vibe Failsafe" logic.

Tuning & Behavior

  • Testing: Set to 5.0 and watch the VIBE message in your Ground Control Station. You can verify if the drone can still maintain its position under high-stress vibration conditions.

SIM_VICON_FAIL

Default 0
Range 0 1

Simulation Vicon Failure (SIM_VICON_FAIL)

Description

SIM_VICON_FAIL cuts the data feed from the external motion capture system.

This is critical for testing indoor drones. If the Vicon system crashes or the drone flies behind an obstacle, the EKF loses its primary position source. This parameter allows you to verify that the drone successfully fails over to Optical Flow or enters a safe landing mode.

  • 0: Healthy.
  • 1: Failed.

SIM_VICON_GLIT

m
Default 0
Range 0 10

Simulation Vicon Position Glitch (SIM_VICON_GLIT)

Description

SIM_VICON_GLIT injects a "Jump" into the external navigation data.

When using an external motion capture system (like Vicon or OptiTrack) for indoor flight, the data is usually perfect. This parameter allows you to simulate a tracking error where the system momentarily reports the drone is in a different location.

Tuning & Behavior

  • Default: 0 (No glitch).
  • Usage: Set to 1.0 or 2.0 to simulate a large tracking jump.
  • Goal: Use this to verify that the EKF (Extended Kalman Filter) correctly rejects the bad data or that the Failsafe logic engages.
  • Note: This applies the glitch to the Down (Vertical) axis.

SIM_VICON_GLIT_X

m
Default 0
Range -100 100

Simulation Vicon Position Glitch X (SIM_VICON_GLIT_X)

Description

SIM_VICON_GLIT_X injects a position error into the external vision system.

This is useful for testing how robust your indoor navigation is to sudden jumps in reported position (e.g. if the Vicon cameras lose calibration or the subject marker is partially occluded).

SIM_VICON_GLIT_Y

m
Default 0
Range -100 100

Simulation Vicon Position Glitch Y (SIM_VICON_GLIT_Y)

Description

SIM_VICON_GLIT_Y injects a lateral position error into the simulated external vision system.

See SIM_VICON_GLIT_X for details.

SIM_VICON_GLIT_Z

m
Default 0
Range -100 100

Simulation Vicon Position Glitch Z (SIM_VICON_GLIT_Z)

Description

SIM_VICON_GLIT_Z injects a vertical position error into the simulated external vision system.

SIM_VICON_POS

m
Default 0
Range 0 5

Simulation Vicon Position Offset (SIM_VICON_POS)

Description

SIM_VICON_POS defines where the "Vicon Marker" is attached to the drone.

In high-precision indoor flight, the position is often reported by an external camera system (Vicon/Optitrack). This parameter allows you to test the compensation for markers that are not mounted at the COG.

SIM_VICON_RATE

Hz
Default 50
Range 1 200

Simulated Vicon Update Rate (SIM_VICON_RATE)

Description

SIM_VICON_RATE sets the data frequency of the virtual motion capture system.

Standard Vicon systems run at 50Hz to 100Hz. A higher rate provides a smoother position estimate for the EKF, while a lower rate tests how the autopilot handles sparse tracking data.

Tuning & Behavior

  • Default Value: 50 Hz.
  • Recommendation: Set to 100 for ultra-stable indoor loiter testing.

SIM_VICON_TMASK

Default 3
Range 0 31

Simulation Vicon Type Mask (SIM_VICON_TMASK)

Description

SIM_VICON_TMASK controls which "Languages" the virtual motion capture system uses to talk to the autopilot.

Different external systems (Vicon, Optitrack, Marvelmind) use different MAVLink packets to report position and speed.

  • Bit 0 (1): VISION_POSITION_ESTIMATE
  • Bit 1 (2): VISION_SPEED_ESTIMATE
  • Bit 2 (4): VICON_POSITION_ESTIMATE
  • Bit 3 (8): VISION_POSITION_DELTA
  • Bit 4 (16): ODOMETRY

Tuning & Behavior

  • Default Value: 3 (Position + Speed estimates).

SIM_VICON_VGLI

m/s
Default 0
Range 0 10

Simulation Vicon Velocity Glitch (SIM_VICON_VGLI)

Description

SIM_VICON_VGLI injects a false "Speed Spike" into the external navigation data.

Even if the drone is hovering perfectly still, this parameter makes the simulated motion capture system report that the drone is suddenly moving vertically at high speed. This tests how the EKF handles conflicting data (accelerometers say "stopped," Vicon says "moving").

Tuning & Behavior

  • Default: 0 m/s.
  • Usage: Set to 5.0 to simulate a tracking error where the system momentarily loses lock and reports a massive velocity spike.
  • Note: This applies the glitch to the Down (Vertical) velocity.

SIM_VICON_VGLI_X

m/s
Default 0
Range -10 10

Simulation Vicon Velocity Glitch X (SIM_VICON_VGLI_X)

Description

SIM_VICON_VGLI_X injects a velocity error into the external vision system.

This tests if the EKF can handle a Vicon system that reports a constant drift in speed (e.g. due to lighting changes or high-speed blur).

SIM_VICON_VGLI_Y

m/s
Default 0
Range -10 10

Simulation Vicon Velocity Glitch Y (SIM_VICON_VGLI_Y)

Description

SIM_VICON_VGLI_Y injects a lateral velocity error into the simulated external vision system.

SIM_VICON_VGLI_Z

m/s
Default 0
Range -10 10

Simulation Vicon Velocity Glitch Z (SIM_VICON_VGLI_Z)

Description

SIM_VICON_VGLI_Z injects a vertical velocity error into the simulated external vision system.

SIM_VICON_YAW

deg
Default 0
Range 0 360

Simulation Vicon Yaw Angle (SIM_VICON_YAW)

Description

SIM_VICON_YAW defines the simulated orientation of the external position source. Useful for testing if the flight controller correctly integrates absolute heading data from a motion capture system.

SIM_VICON_YAWERR

deg
Default 0
Range -180 180

Simulation Vicon Yaw Error (SIM_VICON_YAWERR)

Description

SIM_VICON_YAWERR simulates a misalignment between the Vicon system's north and the drone's IMU north. This tests the EKF's ability to handle rotational offsets in external position data.

SIM_VOLZ_ENA

Default 0
Range 0 1

Simulation Volz Servo Enable (SIM_VOLZ_ENA)

Description

SIM_VOLZ_ENA activates the simulated driver for Volz digital servos.

Normally, SITL assumes standard PWM servos. If you enable this, ArduPilot will communicate with virtual Volz servos via a serial protocol, allowing you to test the serial driver and telemetry feedback in a simulated environment.

SIM_WAVE_AMP

m
Default 0.5
Range 0 5

Simulated Wave Amplitude (SIM_WAVE_AMP)

Description

SIM_WAVE_AMP sets the "Roughness" of the sea.

A value of 1.0 means the peaks of the waves are 1 meter high. Large waves will cause significantly more rocking and may wash over the deck of low-profile boats.

Tuning & Behavior

  • Default Value: 0.5 m.

SIM_WAVE_DIR

deg
Default 0
Range 0 360

Simulated Wave Direction (SIM_WAVE_DIR)

Description

SIM_WAVE_DIR sets the compass bearing of the ocean swell.

  • 0: North waves (moving towards South).
  • 90: East waves.

SIM_WAVE_ENABLE

Default 0
Range 0 1

Simulated Wave Enable (SIM_WAVE_ENABLE)

Description

SIM_WAVE_ENABLE adds "Ocean Swell" to the simulation.

When enabled, virtual boats will pitch and roll as they ride over simulated waves. This is essential for testing "Surface Stability" and verifying that the AHRS/EKF doesn't get disoriented by constant rocking.

Tuning & Behavior

  • 0: Disabled (Glassy water).
  • 1: Enabled.

SIM_WAVE_LENGTH

m
Default 10
Range 1 100

Simulated Wave Length (SIM_WAVE_LENGTH)

Description

SIM_WAVE_LENGTH sets the "Frequency" of the ocean swell.

Short wavelengths (e.g. 5m) create choppy, rapid rocking. Long wavelengths (e.g. 50m) create slow, graceful rises and falls.

Tuning & Behavior

  • Default Value: 10 m.

SIM_WAVE_SPEED

m/s
Default 3
Range 0 20

Simulated Wave Speed (SIM_WAVE_SPEED)

Description

SIM_WAVE_SPEED defines how fast the wave patterns move.

Tuning & Behavior

  • Default Value: 3 m/s.

SIM_WIND_DIR

deg
Default 180
Range 0 360

Simulation Wind Direction (SIM_WIND_DIR)

Description

SIM_WIND_DIR sets the wind bearing.

  • 0: North wind (Blows South).
  • 90: East wind (Blows West).

Tuning & Behavior

  • Default Value: 180 (South wind).

SIM_WIND_DIR_Z

deg
Default 0
Range -90 90

Simulated Vertical Wind Direction (SIM_WIND_DIR_Z)

Description

SIM_WIND_DIR_Z simulates "Thermals" or "Downbursts."

  • 0: Horizontal wind only.
  • 90: Vertical updraft.
  • -90: Vertical downdraft.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Set to 10 or 20 to test your drone's altitude hold against a constant thermal rise.

SIM_WIND_SPD

m/s
Default 0
Range 0 50

Simulation Wind Speed (SIM_WIND_SPD)

Description

SIM_WIND_SPD adds a constant wind to the simulation.

  • 0: Calm day.
  • 10: 10 m/s (22 mph) wind.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Essential for tuning WPNAV_SPEED and checking if your drone can hold position in high winds.

SIM_WIND_T

Default 0
Range 0 2

Simulated Wind Type (SIM_WIND_T)

Description

SIM_WIND_T models how wind speed decreases as you get closer to the ground (due to ground friction).

  • 0: Square Law (Realistic). Wind speed drops off naturally near the surface.
  • 1: None. Constant wind speed at all altitudes.
  • 2: Linear. Constant decrease from SIM_WIND_T_ALT down to zero.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Keep at 0 for realistic landing tests.

SIM_WIND_TC

s
Default 5
Range 1 100

Simulated Wind Time Constant (SIM_WIND_TC)

Description

SIM_WIND_TC controls how quickly the wind "Wanders" between different speeds and directions.

A small value means the wind changes instantly (very gusty). A large value means the wind changes slowly and smoothly over several seconds.

Tuning & Behavior

  • Default Value: 5 seconds.
  • Recommendation: Leave at 5 for realistic atmospheric behavior.

SIM_WIND_TURB

m/s
Default 0
Range 0 50

Simulation Wind Turbulence (SIM_WIND_TURB)

Description

SIM_WIND_TURB makes the wind gusty.

  • 0: Steady laminar flow.
  • 5: Gusts +/- 5 m/s.

Tuning & Behavior

  • Default Value: 0.
  • Testing: Use this to tune your Rate D-Term and Position Controller responsiveness.

SIM_WIND_T_ALT

m
Default 60
Range 0 1000

Simulated Wind Type Altitude (SIM_WIND_T_ALT)

Description

SIM_WIND_T_ALT defines the "Boundary Layer" height.

Above this altitude, the wind speed is constant (SIM_WIND_SPD). Below this altitude, the wind slows down due to ground friction (if SIM_WIND_T is enabled).

Tuning & Behavior

  • Default Value: 60 m.

SIM_WIND_T_COEF

Default 0.01
Range 0 1

Simulated Wind Type Coefficient (SIM_WIND_T_COEF)

Description

SIM_WIND_T_COEF defines the "Roughness" of the ground.

A higher value means the ground slows the wind down more, creating a steeper wind gradient (shear) near the surface.

Tuning & Behavior

  • Default Value: 0.01.

SIM_WOW_PIN

Default -1
Range -1 100

Simulated Weight on Wheels Pin (SIM_WOW_PIN)

Description

SIM_WOW_PIN enables a virtual sensor that detects if the aircraft is physically touching the ground.

This is critical for testing automatic arming/disarming logic and "Landed" state detection. When the drone is on the ground, the virtual pin state is changed.

Tuning & Behavior

  • Default Value: -1 (Disabled).