Skip to content

Safety (Failsafe) Configuration

PX4 has a number of safety features to protect and recover your vehicle if something goes wrong:

  • Failsafes allow you to specify areas and conditions under which you can safely fly, and the action that will be performed if a failsafe is triggered (for example, landing, holding position, or returning to a specified point). The most important failsafe settings are configured in the QGroundControl Safety Setup page. Others must be configured via parameters.
  • Safety switches on the remote control can be used to immediately stop motors or return the vehicle in the event of a problem.

QGroundControl Safety Setup

The QGroundControl Safety Setup page is accessed by clicking the QGroundControl icon, Vehicle Setup, and then Safety in the sidebar. This includes many of the most important failsafe settings (battery, RC loss etc.) and the settings for the triggered actions Return and Land.

Safety Setup(QGC)

Failsafe Actions

When a failsafe is triggered, the default behavior (for most failsafes) is to enter Hold for COM_FAIL_ACT_T seconds before performing an associated failsafe action. This gives the user time to notice what is happening and override the failsafe if needed. In most cases this can be done by using RC or a GCS to switch modes (note that during the failsafe-hold, moving the RC sticks does not trigger an override).

The list below shows the set of all failsafe actions, ordered in increasing severity. Note that different types of failsafe may not support all of these actions.

ActionDescription
None/DisabledNo action. The failsafe will be ignored.
WarningA warning message will be sent (i.e. to QGroundControl).
Hold modeThe vehicle will enter Hold mode (MC) or Hold mode (FW) and hover or circle, respectively. VTOL vehicles will hold according to their current mode (MC/FW).
Return modeThe vehicle will enter Return mode. Return behaviour can be set in the Return Home Settings (below).
Land modeThe vehicle will enter Land mode (MC) or Land mode (FW), and land. A VTOL will first transition to MC mode.
DisarmStops the motors immediately.
Flight terminationTurns off all controllers and sets all PWM outputs to their failsafe values (e.g. PWM_MAIN_FAILn, PWM_AUX_FAILn). The failsafe outputs can be used to deploy a parachute, landing gear or perform another operation. For a fixed-wing vehicle this might allow you to glide the vehicle to safety.

If multiple failsafes are triggered, the more severe action is taken. For example if both RC and GPS are lost, and manual control loss is set to Return mode and GCS link loss to Land, Land is executed.

TIP

The exact behavior when different failsafes are triggered can be tested with the Failsafe State Machine Simulation.

Return Mode Settings

Return is a common failsafe action that engages Return mode to return the vehicle to the home position. The default settings for each vehicle are usually suitable, though for fixed wing vehicles you will usually need to define a mission landing.

TIP

If you want to change the configuration you should carefully read the Return mode documentation for your vehicle type to understand the options.

QGC allows users to set some aspects of the return mode and landing behaviour, such as the altitude to fly back, and the loiter time if you need to deploy landing gear.

Safety - Return Home Settings (QGC)

Land Mode Settings

Land at the current position is a common failsafe action (in particular for multicopters), that engages Land Mode. The default settings for each vehicle are usually suitable.

TIP

If you want to change the configuration you should carefully read the Land mode documentation for your vehicle type to understand the options.

QGC allows users to set some aspects of the landing behaviour, such as the time to disarm after landing and the descent rate (for multicopters only).

Safety - Land Mode Settings (QGC)

Battery Failsafes

Battery level failsafe

The low battery failsafe is triggered when the battery capacity drops below battery failafe level values. You can configure both the levels and the failsafe actions at each level in QGroundControl.

Safety - Battery (QGC)

The most common configuration is to set the values and action as above (with Warn > Failsafe > Emergency), and to set the Failsafe Action to warn at "warn level", trigger Return mode at "Failsafe level", and land immediately at "Emergency level".

The settings and underlying parameters are shown below.

SettingParameterDescription
Failsafe ActionCOM_LOW_BAT_ACTWarn, Return, or Land based when capacity drops below the trigger levels.
Battery Warn LevelBAT_LOW_THRPercentage capacity for warnings (or other actions).
Battery Failsafe LevelBAT_CRIT_THRPercentage capacity for Return action (or other actions if a single action selected).
Battery Emergency LevelBAT_EMERGEN_THRPercentage capacity for triggering Land (immediately) action.

Flight Time Failsafes

There are several other "battery related" failsafe mechanisms that may be configured using parameters:

  • The "remaining flight time for safe return" failsafe (COM_FLTT_LOW_ACT) is engaged when PX4 estimates that the vehicle has just enough battery remaining for a return mode landing. You can configure this to ignore the failsafe, warn, or engage Return mode.
  • The "maximum flight time failsafe" (COM_FLT_TIME_MAX) allows you to set a maximum flight time after takeoff, at which the vehicle will automatically enter return mode (it will also "warn" at 90% of this time). This is like a "hard coded" estimate of the total flight time in a battery. The feature is disabled by default.
  • The "minimum battery" for arming parameter (COM_ARM_BAT_MIN) prevents arming in the first place if the battery level is below the specified value.

The settings and underlying parameters are shown below.

SettingParameterDescription
Low flight time for safe return actionCOM_FLTT_LOW_ACTAction when return mode can only just reach safety with remaining battery. 0: None, 1: Warning, 3: Return mode (default).
Maximum flight time failsafe levelCOM_FLT_TIME_MAXMaximum allowed flight time before Return mode will be engaged, in seconds. -1: Disabled (default).

Manual Control Loss Failsafe

The manual control loss failsafe may be triggered if the connection to the RC transmitter or joystick is lost, and there is no fallback. If using an RC transmitter this is triggered if the RC transmitter link is lost. If using joysticks connected over a MAVLink data link, this is triggered if the joysticks are disconnected or the data link is lost.

INFO

PX4 and the receiver may also need to be configured in order to detect RC loss: Radio Setup > RC Loss Detection.

Safety - RC Loss (QGC)

The QGCroundControl Safety UI allows you to set the failsafe action and RC Loss timeout. Users that want to disable the RC loss failsafe in specific automatic modes (mission, hold, offboard) can do so using the parameter COM_RCL_EXCEPT.

Additional (and underlying) parameter settings are shown below.

ParameterSettingDescription
COM_RC_LOSS_TManual Control Loss TimeoutTime after last setpoint received from the selected manual control source after which manual control is considered lost. This must be kept short because the vehicle will continue to fly using the old manual control setpoint until the timeout triggers.
COM_FAIL_ACT_TFailsafe Reaction DelayDelay in seconds between failsafe condition being triggered (COM_RC_LOSS_T) and failsafe action (RTL, Land, Hold). In this state the vehicle waits in hold mode for the manual control source to reconnect. This might be set longer for long-range flights so that intermittent connection loss doesn't immediately invoke the failsafe. It can be to zero so that the failsafe triggers immediately.
NAV_RCL_ACTFailsafe ActionDisabled, Loiter, Return, Land, Disarm, Terminate.
COM_RCL_EXCEPTRC Loss ExceptionsSet the modes in which manual control loss is ignored: Mission, Hold, Offboard.

The Data Link Loss failsafe is triggered if a telemetry link (connection to ground station) is lost.

Safety - Data Link Loss (QGC)

The settings and underlying parameters are shown below.

SettingParameterDescription
Data Link Loss TimeoutCOM_DL_LOSS_TAmount of time after losing the data connection before the failsafe will trigger.
Failsafe ActionNAV_DLL_ACTDisabled, Hold mode, Return mode, Land mode, Disarm, Terminate.

The following settings also apply, but are not displayed in the QGC UI.

SettingParameterDescription
Mode exceptions for DLL failsafeCOM_DLL_EXCEPTSet modes where DL loss will not trigger a failsafe.

Geofence Failsafe

The Geofence Failsafe is triggered when the drone breaches a "virtual" perimeter. In its simplest form, the perimeter is set up as a cylinder centered around the home position. If the vehicle moves outside the radius or above the altitude the specified Failsafe Action will trigger.

Safety - Geofence (QGC)

TIP

PX4 separately supports more complicated Geofence geometries with multiple arbitrary polygonal and circular inclusion and exclusion areas: Flying > Geofence.

The settings and underlying geofence parameters are shown below.

SettingParameterDescription
Action on breachGF_ACTIONNone, Warning, Hold mode, Return mode, Terminate, Land.
Max RadiusGF_MAX_HOR_DISTHorizontal radius of geofence cylinder. Geofence disabled if 0.
Max AltitudeGF_MAX_VER_DISTHeight of geofence cylinder. Geofence disabled if 0.

INFO

Setting GF_ACTION to terminate will kill the vehicle on violation of the fence. Due to the inherent danger of this, this function is disabled using CBRK_FLIGHTTERM, which needs to be reset to 0 to really shut down the system.

The following settings also apply, but are not displayed in the QGC UI.

SettingParameterDescription
Geofence sourceGF_SOURCESet whether position source is estimated global position or direct from the GPS device.
Preemptive geofence triggeringGF_PREDICT(Experimental) Trigger geofence if current motion of the vehicle is predicted to trigger the breach (rather than late triggering after the breach).
Circuit breaker for flight terminationCBRK_FLIGHTTERMEnables/Disables flight termination action (disabled by default).

Position (GNSS) Loss Failsafe

The Position Loss Failsafe is triggered if the quality of the PX4 position estimate falls below acceptable levels (this might be caused by GPS loss) while in a mode that requires an acceptable position estimate. The sections below cover first the trigger and then the failsafe action taken by the controller.

Position Loss Failsafe Trigger

There are basically two mechanisms in PX4 to trigger position failsafes:

  • A timeout since the last sensor data was fused that provides direct speed or horizontal position measurements. Sensors that fall into that category are: GNSS, optical flow, airspeed, VIO, auxiliary global position.
  • The estimated horizontal position accuracy exceeds a certain threshold. This check is only done on hovering systems (rotary wing vehicles or VTOLs in hover phase).

The relevant parameters shown below.

ParameterDescription
EKF2_NOAID_TOUTMaximum inertial dead-reckoning time, so the time after the last data sample was received of any sensor that constrains the velocity drift [microseconds].
COM_POS_FS_EPHHorizontal position error threshold for hovering vehicles (Multicopters and VTOLs in hover). Fixed-wing vehicles have this value set to infinity.

Position Loss Failsafe Action

Multicopters will switch to Altitude mode if a height estimate is available, otherwise Stabilized mode.

Fixed-wing planes, and VTOLs not configured to land in hover (NAV_FORCE_VT), have a parameter (FW_GPSF_LT) that defines how long they will loiter (circle with a constant roll angle (FW_GPSF_R) at the current altitude) after losing position before attempting to land. If VTOLs have are configured to switch to hover for landing (NAV_FORCE_VT) then they will first transition and then descend.

The relevant parameters for all vehicles shown below.

Parameters that only affect Fixed-wing vehicles:

ParameterDescription
FW_GPSF_LTLoiter time (waiting for GPS recovery before it goes into land or flight termination). Set to 0 to disable.
FW_GPSF_RFixed roll/bank angle while circling.

Offboard Loss Failsafe

The Offboard Loss Failsafe is triggered if the offboard link is lost while under Offboard control. Different failsafe behaviour can be specified based on whether or not there is also an RC connection available.

The relevant parameters are shown below:

ParameterDescription
COM_OF_LOSS_TDelay after loss of offboard connection before the failsafe is triggered.
COM_OBL_RC_ACTFailsafe action if RC is available: Position mode, Altitude mode, Manual mode, Return mode, Land mode, Hold mode.

Traffic Avoidance Failsafe

The Traffic Avoidance Failsafe allows PX4 to respond to transponder data (e.g. from ADSB transponders) during missions.

The relevant parameters are shown below:

ParameterDescription
NAV_TRAFF_AVOIDSet the failsafe action: Disabled, Warn, Return mode, Land mode.

Quad-chute Failsafe

Failsafe for when a VTOL vehicle can no longer fly in fixed-wing mode, perhaps due to the failure of a pusher motor, airspeed sensor, or control surface. If the failsafe is triggered, the vehicle will immediately switch to multicopter mode and execute the action defined in parameter COM_QC_ACT.

INFO

The quad-chute can also be triggered by sending a MAVLINK MAV_CMD_DO_VTOL_TRANSITION message with param2 set to 1.

The parameters that control when the quad-chute will trigger are listed in the table below.

ParameterDescription
COM_QC_ACTQuad-chute action after switching to multicopter flight. Can be set to: Warning, Return, Land, Hold.
VT_FW_QC_HMAXMaximum quad-chute height, below which the quad-chute failsafe cannot trigger. This prevents high altitude quad-chute descent, which can drain the battery (and itself cause a crash). The height is relative to ground, home, or the local origin (in preference order, depending on what is available).
VT_QC_ALT_LOSSUncommanded descent quad-chute altitude threshold.

In altitude controlled modes, such as Hold mode, Position mode, Altitude mode, or Mission mode, a vehicle should track its current "commanded" altitude setpoint. The quad chute failsafe is triggered if the vehicle falls too far below the commanded setpoint (by the amount defined in this parameter).

Note that the quad-chute is only triggered if the vehicle continuously loses altitude below the commanded setpoint; it is not triggered if the commanded altitude setpoint increases faster than the vehicle can follow.
VT_QC_T_ALT_LOSSAltitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight. The quad-chute is triggered if the vehicle falls this far below its initial altitude before completing the transition.
VT_FW_MIN_ALTMinimum altitude above Home for fixed-wing flight. When the altitude drops below this value in fixed-wing flight the vehicle a quad-chute is triggered.
VT_FW_QC_RAbsolute roll threshold for quad-chute triggering in FW mode.
VT_FW_QC_PAbsolute pitch threshold for quad-chute triggering in FW mode.

High Wind Failsafe

The high wind failsafe can trigger a warning and/or other mode change when the wind speed exceeds the warning and maximum wind-speed threshhold values. The relevant parameters are listed in the table below.

ParameterDescription
COM_WIND_MAXWind speed threshold that triggers failsafe action, in m/s (COM_WIND_MAX_ACT).
COM_WIND_MAX_ACTHigh wind failsafe action (following COM_WIND_MAX trigger). Can be set to: 0: None (Default), 1: Warning, 2: Hold, 3: Return, 4: Terminate, 5: Land.
COM_WIND_WARNWind speed threshold that triggers periodic failsafe warning.

Failure Detector

The failure detector allows a vehicle to take protective actions if it unexpectedly flips, detects a motor failure, or if it is notified by an external failure detection system.

During flight, the failure detector can be used to trigger flight termination if failure conditions are met, which may then launch a parachute or perform some other action.

INFO

Acting on a detected failure during flight is deactivated by default (enable by setting the parameter: CBRK_FLIGHTTERM=0).

During takeoff the failure detector attitude trigger invokes the disarm action if the vehicle flips (disarm kills the motors but, unlike flight termination, will not launch a parachute or perform other failure actions). Note that this check is always enabled on takeoff, irrespective of the CBRK_FLIGHTTERM parameter.

The failure detector is active in all vehicle types and modes, except for those where the vehicle is expected to do flips (i.e. Acro mode (MC), Acro mode (FW), and Manual (FW)).

Attitude Trigger

The failure detector can be configured to trigger if the vehicle attitude exceeds predefined pitch and roll values for longer than a specified time.

The relevant parameters are shown below:

ParameterDescription
CBRK_FLIGHTTERMFlight termination circuit breaker. Unset from 121212 (default) to enable flight termination due to FailureDetector or FMU loss.
FD_FAIL_PMaximum allowed pitch (in degrees).
FD_FAIL_RMaximum allowed roll (in degrees).
FD_FAIL_P_TTRITime to exceed FD_FAIL_P for failure detection (default 0.3s).
FD_FAIL_R_TTRITime to exceed FD_FAIL_R for failure detection (default 0.3s).

Motor Failure Trigger

The failure detector can be configured to detect a motor failure while armed (and trigger an associated action) in the following conditions:

  • A 300 ms timeout occurs in telemetry from an ESC that was previously available.

  • The input current in the telemetry of an ESC which was previously positive gets too low for more than FD_ACT_MOT_TOUT ms. The "too low" condition is defined by:

    text
    {esc current} < {parameter FD_ACT_MOT_C2T} * {motor command between 0 and 1}
ParameterDescription
FD_ACT_ENEnable/disable the motor failure trigger completely.
FD_ACT_MOT_THRMinimum normalized [0,1] motor command below which motor under current is ignored.
FD_ACT_MOT_C2TScale between normalized [0,1] motor command and expected minimally reported currrent when the rotor is healthy.
FD_ACT_MOT_TOUTTime in miliseconds for which the under current detection condition needs to stay true.
CA_FAILURE_MODEConfigure to not only warn about a motor failure but remove the first motor that detects a failure from the allocation effectiveness which turns off the motor and tries to operate the vehicle without it until disarming the next time.

External Automatic Trigger System (ATS)

The failure detector, if enabled, can also be triggered by an external ATS system. The external trigger system must be connected to flight controller port AUX5 (or MAIN5 on boards that do not have AUX ports), and is configured using the parameters below.

INFO

External ATS is required by ASTM F3322-18. One example of an ATS device is the FruityChutes Sentinel Automatic Trigger System (SATS-MINI).

ParameterDescription
FD_EXT_ATS_ENEnable PWM input on AUX5 or MAIN5 (depending on board) for engaging failsafe from an external automatic trigger system (ATS). Default: Disabled.
FD_EXT_ATS_TRIGThe PWM threshold from external automatic trigger system for engaging failsafe. Default: 1900 ms.

Mission Feasibility Checks

A number of checks are run to ensure that a mission can only be started if it is feasible. For example, the checks ensures that the first waypoint isn't too far away, and that the mission flight path doesn't conflict with any geofences.

As these are not strictly speaking "failsafes" they are documented in Mission Mode (FW) > Mission Feasibility Checks and Mission Mode (MC) > Mission Feasibility Checks.

Emergency Switches

Remote control switches can be configured (as part of QGroundControl Flight Mode Setup) to allow you to take rapid corrective action in the event of a problem or emergency; for example, to stop all motors, or activate Return mode.

This section lists the available emergency switches.

Kill Switch

A kill switch immediately stops all motor outputs — if flying, the vehicle will start to fall!

By default the motors will restart if the switch is reverted within 5 seconds, after which the vehicle will automatically disarm, and you will need to arm it again in order to start the motors.

ParameterDescription
COM_KILL_DISARMTimeout value for disarming after kill switch is engaged. Default: 5 seconds.

INFO

There is also a Kill Gesture, which cannot be reverted.

Arm/Disarm Switch

The arm/disarm switch is a direct replacement for the default stick-based arming/disarming mechanism (and serves the same purpose: making sure there is an intentional step involved before the motors start/stop). It might be used in preference to the default mechanism because:

  • Of a preference of a switch over a stick motion.
  • It avoids accidentally triggering arming/disarming in-air with a certain stick motion.
  • There is no delay (it reacts immediately).

The arm/disarm switch immediately disarms (stop) motors for those flight modes that support disarming in flight. This includes:

  • Manual mode
  • Acro mode
  • Stabilized

For modes that do not support disarming in flight, the switch is ignored during flight, but may be used after landing is detected. This includes Position mode and autonomous modes (e.g. Mission, Land etc.).

INFO

Auto disarm timeouts (e.g. via COM_DISARM_LAND) are independent of the arm/disarm switch - ie even if the switch is armed the timeouts will still work.

Return Switch

A return switch can be used to immediately engage Return mode.

Kill Gesture

A kill gesture immediately stops all motor outputs — if flying, the vehicle will start to fall!

The action cannot be reverted without a reboot (this differs from a Kill Switch, where the operation can be reverted within the time period defined by COM_KILL_DISARM).

ParameterDescription
MAN_KILL_GEST_TTime to hold sticks in gesture position before killing the motors. Default: -1 seconds (Disabled).

Arming/Disarming Settings

The commander module has a number of parameters prefixed with COM_ARM that configure whether the vehicle can arm at all, and under what conditions (note that some parameters named with the prefix COM_ARM are used to arm other systems). Parameters prefixed with COM_DISARM_ affect disarming behaviour.

Auto-Disarming Timeouts

You can set timeouts to automatically disarm a vehicle if it is too slow to takeoff, and/or after landing (disarming the vehicle removes power to the motors, so the propellers won't spin).

The relevant parameters are shown below:

ParameterDescription
COM_DISARM_LANDTimeout for auto-disarm after landing.
COM_DISARM_PRFLTTimeout for auto disarm if vehicle is too slow to takeoff.

Arming Pre-Conditions

These parameters can be used to set conditions that prevent arming.

ParameterDescription
COM_ARMABLEEnable arming (at all). 0: Disabled, 1: Enabled (default).
COM_ARM_BAT_MINMinimum battery level for arming. 0: Disabled (default). Values: 0-0.9,
COM_ARM_WO_GPSEnable arming without GPS. 0: Disabled, 1: Enabled (default).
COM_ARM_MIS_REQRequire valid mission to arm. 0: Disabled (default), 1: Enabled .
COM_ARM_SDCARDRequire SD card to arm. 0: Disabled (default), 1: Warning, 2: Enabled.
COM_ARM_AUTH_REQRequires arm authorisation from an external (MAVLink) system. Flag to allow arming (at all). 1: Enabled, 0: Disabled (default). Associated configuration parameters are prefixed with COM_ARM_AUTH_.
COM_ARM_ODIDRequire healthy Remote ID system to arm. 0: Disabled (default), 1: Warning, 2: Enabled.

In addition there are a number of parameters that configure system and sensor limits that make prevent arming if exceeded: COM_CPU_MAX, COM_ARM_IMU_ACC, COM_ARM_IMU_GYR, COM_ARM_MAG_ANG, COM_ARM_MAG_STR.

Further Information