Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/Ardupilot/ardupilot/llms.txt

Use this file to discover all available pages before exploring further.

ArduPilot uses two layers of protection to keep the vehicle and people around it safe: arming checks that prevent the vehicle from arming when conditions are unsafe, and failsafes that respond automatically when a critical condition occurs during flight. Both systems are configurable, but their defaults are chosen conservatively—disabling or weakening them should only be done with a thorough understanding of the consequences.
Arming checks and failsafes are safety-critical systems. Incorrectly configuring them can result in flyaway events, crashes, or injury. Always test configuration changes in a controlled environment before flying over people or property.

Arming checks (AP_Arming)

Before a vehicle can arm it must pass a series of pre-arm checks defined in AP_Arming (libraries/AP_Arming/AP_Arming.h). Each check is a bit in the ARMING_CHECK bitmask parameter. Setting the bit to 1 enables the check; the vehicle refuses to arm if the check fails and reports the reason as a STATUSTEXT pre-arm message.
// From libraries/AP_Arming/AP_Arming.h
enum class Check {
    BARO        = (1U << 1),   // barometer healthy
    COMPASS     = (1U << 2),   // compass calibrated and consistent
    GPS         = (1U << 3),   // GPS lock (3D fix)
    INS         = (1U << 4),   // IMU calibrated and consistent
    PARAMETERS  = (1U << 5),   // no bad parameter values
    RC          = (1U << 6),   // RC calibrated and in range
    VOLTAGE     = (1U << 7),   // board voltage within limits
    BATTERY     = (1U << 8),   // battery level above minimum
    LOGGING     = (1U << 10),  // logging available (SD card present)
    SWITCH      = (1U << 11),  // safety switch in correct state
    GPS_CONFIG  = (1U << 12),  // GPS serial port configured
    SYSTEM      = (1U << 13),  // system checks (scheduler, memory)
    MISSION     = (1U << 14),  // mission available if required
    RANGEFINDER = (1U << 15),  // rangefinder healthy if required
};
Requires a 3D GPS fix with HDOP at or below GPS_HDOP_GOOD (default: 140, i.e. 1.40). The vehicle will refuse to arm in GPS-required modes (Loiter, Auto, Guided, RTL) without this. The check also verifies that GPS velocity is consistent with the IMU.
Verifies that the compass is calibrated (offsets set), that the field strength is within expected bounds, and that multiple compasses agree with each other. The expected field strength is derived from the vehicle’s location using the world magnetic model.
Confirms that all RC channels are within their calibrated trim and range values. A channel output of exactly 0 PWM typically indicates a disconnected receiver or an uncalibrated channel.
Verifies the barometer is healthy and reading a plausible atmospheric pressure. The check also ensures the baro has had time to settle after powerup.
Confirms that the Extended Kalman Filter has initialised and that attitude, velocity, and position variance values are below the threshold set by FS_EKF_THRESH. The EKF must be healthy before arming is permitted.
Confirms that the measured battery voltage (if a battery monitor is configured) is above the failsafe voltage threshold. This prevents arming with a flat pack.

Pre-arm messages

When a check fails ArduPilot sends a STATUSTEXT message with the reason and the prefix "PreArm: ". The same message appears in the GCS console and on the OSD. Common examples:
PreArm: GPS: not enough sats (5)
PreArm: Compass not calibrated
PreArm: RC not calibrated
PreArm: EKF attitude is bad
PreArm: Logging failed
To clear a pre-arm failure, resolve the underlying condition (e.g. wait for more GPS satellites, recalibrate the compass) and the check will pass automatically on the next evaluation cycle.
In MAVProxy you can run arm check to see which checks are currently failing without attempting to arm the vehicle.

Failsafe types

Failsafes respond to in-flight emergencies. Each failsafe type has a dedicated parameter to enable it and configure the action taken. Actions are applied only to an armed, flying vehicle; a disarmed vehicle on the ground is simply disarmed further if already disarmed.
Trigger: The PWM value on the throttle channel falls below FS_THR_VALUE (default: 975 µs) for more than a brief debounce period. This indicates a lost RC link (most RC systems drive the throttle channel to a low value on signal loss).Parameter: FS_THR_ENABLE
ValueAction
0Disabled
1Always RTL
3Always Land
4SmartRTL, or RTL if SmartRTL unavailable
5SmartRTL, or Land if SmartRTL unavailable
6Auto DO_LAND_START / DO_RETURN_PATH_START, or RTL
7Brake, then Land
The FS_OPTIONS bitmask allows exceptions: for example, allowing a mission in Auto mode to continue rather than triggering RTL.Recovery: When the RC link is restored ArduPilot logs the resolved event and sends "Radio Failsafe Cleared". The pilot can switch modes normally.
Trigger: Battery voltage falls below BATT_LOW_VOLT or remaining capacity falls below BATT_LOW_MAH (low-level warning), or below BATT_CRT_VOLT/BATT_CRT_MAH (critical level).Each battery monitor instance has its own BATTn_FS_LOW_ACT and BATTn_FS_CRT_ACT parameters controlling the action at each level. Typical actions are RTL at the low level and Land at the critical level.ArduPilot treats the battery failsafe as higher priority than the RC failsafe—if both trigger simultaneously the battery action takes precedence during a landing sequence.Recovery: The battery failsafe clears only when the voltage recovers above the threshold, which typically does not happen in the field. Plan for a one-way event.
Trigger: No heartbeat or valid MAVLink traffic is received from the GCS (identified by SYSID_MYGCS) for longer than FS_GCS_TIMEOUT seconds (default: 5 s). The failsafe only activates if the GCS was previously connected—it will not trigger on a vehicle that has never seen a GCS heartbeat.Parameter: FS_GCS_ENABLE
ValueAction
0Disabled
1RTL
3SmartRTL, or RTL
4SmartRTL, or Land
5Land
6Auto DO_LAND_START / DO_RETURN_PATH_START, or RTL
7Brake, then Land
The FS_OPTIONS parameter can allow autonomous missions in Auto mode or pilot-controlled modes to continue despite a GCS link loss.Recovery: ArduPilot sends "GCS Failsafe Cleared" when the GCS heartbeat is detected again.
Trigger: The Extended Kalman Filter reports that compass variance, velocity variance, or position variance exceeds the threshold set by FS_EKF_THRESH (default: 0.8). This indicates that the EKF can no longer produce a reliable state estimate—typically caused by compass interference, GPS spoofing, or rapid acceleration.Parameter: FS_EKF_ACTION
ValueAction
0Report only
1Land if current mode requires position
2AltHold if current mode requires position
3Land from all modes
The default action (Land) switches to Land mode when the EKF fails in a GPS-dependent mode. AltHold is an alternative that allows the pilot to retain manual control of altitude without GPS.FS_EKF_THRESH accepts values between 0 (disabled) and 1.0. A lower threshold is more sensitive but may produce false triggers in turbulence.Parameter: FS_EKF_THRESH
ValueSensitivity
0Disabled
0.6Strict
0.8Default
1.0Relaxed
Trigger: Terrain data is required by the active flight mode (Auto or Guided with terrain-following enabled) but is unavailable from the database for longer than FS_TERRAIN_TIMEOUT_MS milliseconds.Action: The vehicle switches to RTL. This failsafe cannot be disabled independently; it is always active when a mode with requires_terrain_failsafe() returning true is active.Terrain data is sourced from the SD card terrain database (AP_Terrain) downloaded in advance from SRTM data via the GCS.
Trigger: Excessive vibration is detected in the IMU data, indicating that the EKF’s inertial navigation solution may be compromised. Enabled by FS_VIBE_ENABLE (default: 1).Action: The vehicle switches to Land mode. This is a safety measure for situations where vibration is severe enough to cause altitude errors or control instability.

Advanced failsafe (AP_AdvancedFailsafe)

Fixed-wing vehicles (ArduPlane) support an additional AP_AdvancedFailsafe system that adds geo-fence breach and GPS-glitch responses on top of the standard failsafes. The AFS is enabled by the AFS_ENABLE parameter and adds configurable terminal actions (termination or loiter) when the vehicle leaves defined boundaries. ArduCopter has a limited AFS implementation (AP_AdvancedFailsafe_Copter) guarded by AP_COPTER_ADVANCED_FAILSAFE_ENABLED.

Key failsafe parameters

ParameterDefaultDescription
FS_THR_ENABLE1 (RTL)RC throttle failsafe action
FS_THR_VALUE975 µsThrottle channel PWM threshold
FS_GCS_ENABLE0 (disabled)GCS heartbeat failsafe action
FS_GCS_TIMEOUT5 sSeconds before GCS failsafe triggers
FS_EKF_ACTION1 (Land)EKF variance failsafe action
FS_EKF_THRESH0.8EKF variance threshold
FS_CRASH_CHECK1 (enabled)Disarm if crash detected
FS_VIBE_ENABLE1 (enabled)Switch to Land on excess vibration
FS_OPTIONSBitmask to allow exceptions (e.g. continue mission)
ARMING_CHECKall enabledBitmask of pre-arm checks to perform
The FS_OPTIONS bitmask allows nuanced control over failsafe interactions. For example, bit 0 allows landing to continue through an RC failsafe, and bit 2 allows an Auto mission to continue through an RC failsafe. Consult the parameter description in your GCS for the full bitmask definition.

Build docs developers (and LLMs) love