Skip to content

安全配置(故障保护)

PX4有许多安全功能,可以在发生故障时保护并恢复您的机体:

  • _故障保护_允许您指定可以安全飞行的区域和条件,以及在触发故障保护时将执行的操作(例如着陆、定点悬停或返回指定点)。 最重要的故障保护设置在 QGroundControl安全设置页面中配置。 其他设置必须通过参数页面配置。
  • 安全开关 在遥控器上可以用于立即停止发动机或在出现问题时返回车辆。

故障保护动作

当触发故障保护时, 默认行为 (针对大多数故障保护情况) 是在执行相关故障保护动作之前保持 COM_FAIL_ACT_T 秒钟。 这使用户有时间注意到正在发生的情况,并在需要时取消故障保护。 在大多数情况下,可以通过使用 RC或 GCS 切换模式来做到这一点(注意在故障保护保持期间, 移动 RC操纵杆不会触发取消操作)。

下面的列表显示了所有故障保护动作的集合,按其严重程度升序排列。 请注意,不同类型的故障保护可能无法支持所有这些操作。

动作描述
无/禁用无操作. 故障保护将被忽略。
警告警告信息将会被发送(例如到 QGroundControl)。
保持模式载具将分别进入 保持模式 (MC)保持模式 (FW) 和悬停或圆运动。 VTOL车辆将保持其目前的模式(MC/FW)。
返航模式载具将进入 返航模式。 返航行为可以在返回原点设置(如下文所示)中设置。
降落模式载具将进入 降落模式 (MC)降落模式 (FW) 并着陆。 VTAL 将首先过渡到 MC 模式。
Disarm马达立即停止。
飞行终止关闭所有控制器,并将所有PWM输出设置为其故障保护安全值(例如, PWM_MAIN_FAILn, PWM_AUX_FAILn)。 故障保护输出可用于启动降落伞、起落架或执行其他操作。 对于固定翼飞行器,这可能允许您将机体滑翔至安全位置。

如果多个故障保险被触发,将采取高级别的操作。 例如, RC和 GPS 都丢失, 手动控制丢失设置为 返航模式 和 GCS 链路丢失到 降落模式, 将土执行降落着陆。

TIP

当不同的故障保护被触发时精确的动作行为,可以通过故障保护状态机仿真测试。

QGroundControl 安全设置

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

Safety Setup(QGC)

低电量故障保护

The low battery failsafe is triggered when the battery capacity drops below one (or more warning) level values.

Safety - Battery (QGC)

The most common configuration is to set the values and action as above (with Warn > Failsafe > Emergency). With this configuration the failsafe will trigger warning, then return, and finally landing if capacity drops below the respective levels.

It is also possible to set the Failsafe Action to warn, return, or land when the Battery Failsafe Level failsafe level is reached.

The settings and underlying parameters are shown below.

设置参数描述
故障保护动作COM_LOW_BAT_ACT当电池电量过低时,根据下面的每个水平值执行警告、返航、降落三者之一,或分别设置警告、返航或降落。
电池警告水平BAT_LOW_THR需做出警告(或其他动作)的电量百分比。
电池故障保护水平BAT_CRIT_THR电量低于该百分比则返航(或者执行其他事前选择动作)。
电量紧急水平BAT_EMERGEN_THR电量低于该百分比则(立即)触发降落动作。

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.

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.

参数设置描述
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_ACT故障保护动作Disabled, 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.

设置参数描述
数据链路丢失超时COM_DL_LOSS_T数据连接断开后到故障保护触发之前的时间。
故障保护动作NAV_DLL_ACTDisabled, Hold mode, Return mode, Land mode, Disarm, Terminate.

地理围栏故障保护

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)

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.

设置参数描述
冲出围栏时的响应动作GF_ACTIONNone, Warning, Hold mode, Return mode, Terminate, Land.
最大半径GF_MAX_HOR_DIST地理围栏圆柱体的水平半径。 如果为 0,则禁用地理围栏。
最大高度GF_MAX_VER_DIST地理围栏圆柱体的高度。 如果为 0,则禁用地理围栏。

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.

设置参数描述
地理围栏来源GF_SOURCE设置定位是来自全局位置估计还是直接来自 GPS 设备。
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).
飞行终止断路器CBRK_FLIGHTTERM启用/禁用飞行终止操作(默认禁用)。

返航设置

Return is a common failsafe action that engages Return mode to return the vehicle to the home position. This section shows how to set the land/loiter behaviour after returning.

Safety - Return Home Settings (QGC)

The settings and underlying parameters are shown below:

设置参数描述
爬升高度RTL_RETURN_ALT返航飞行时,机体上升到该最低高度(如果低于)。
返航行为Choice list of Return then: Land, Loiter and do not land, or Loiter and land after a specified time.
悬停高度RTL_DESCEND_ALT如果选择了返航并悬停,您还可以指定机体保持的高度。
悬停时间RTL_LAND_DELAY如果选择返航并悬停随后降落,您还可以指定机体将保持悬停多长时间。

The return behaviour is defined by RTL_LAND_DELAY. If negative the vehicle will land immediately. Additional information can be found in Return mode.

降落模式设置

Land at the current position is a common failsafe action (in particular for multicopters), that engages Land Mode. This section shows how to control when and if the vehicle automatically disarms after landing. For Multicopters (only) you can additionally set the descent rate.

Safety - Land Mode Settings (QGC)

The settings and underlying parameters are shown below:

设置参数描述
几秒后锁定COM_DISARM_LAND选中复选框以指定机体在降落后上锁。 该值必须是非零的,但可以是小于一秒的小数。
Landing Descent Rate (MC only)MPC_LAND_SPEEDRate of descent.

其他故障保护设置

This section contains information about failsafe settings that cannot be configured through the QGroundControl Safety Setup page.

位置(GPS)丢失故障保护

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 failure action is controlled by COM_POSCTL_NAVL, based on whether RC control is assumed to be available (and altitude information):

  • 0:遥控控制可用。 Switch to Altitude mode if a height estimate is available, otherwise Stabilized mode.
  • 1: Remote control not available. Switch to Descend mode if a height estimate is available, otherwise enter flight termination. Descend mode is a landing mode that does not require a position estimate.

Fixed-wing vehicles and VTOLs in fixed-wing flight additionally 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.

参数描述
COM_POS_FS_DELAY失去位置后到触发故障保护前的延迟。
COM_POSCTL_NAVL执行任务期间的位置控制导航丢失响应。 值:0——假设使用遥控,1——假设没有遥控。

Parameters that only affect Fixed-wing vehicles:

参数描述
FW_GPSF_LTLoiter time (waiting for GPS recovery before it goes into land or flight termination). 设置为 0 以禁用。
FW_GPSF_R以一定的横滚/侧倾角盘旋。

Offboard 中断故障保护

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:

参数描述
COM_OF_LOSS_TOffboard 连接中断后到触发故障保护前的延迟。
COM_OBL_RC_ACT如果遥控可用,则故障保护动作:定点模式、定高模式、手动模式、返航模式、降落模式、保持模式。

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.

交通规避故障保护

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

The relevant parameters are shown below:

参数描述
NAV_TRAFF_AVOID设置故障保护动作:禁用、警告、返航模式、降落模式。

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.

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.

参数描述
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.

故障检测器

The failure detector allows a vehicle to take protective action(s) if it unexpectedly flips, 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.

Failure detection 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)).

姿态触发器

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:

参数描述
CBRK_FLIGHTTERM飞行终止断路器。 从 121212(默认)取消设置,以启用由于故障检测器或 FMU 丢失而导致的飞行终止。
FD_FAIL_P最大允许俯仰角(角度制)。
FD_FAIL_R最大允许横滚角(角度制)。
FD_FAIL_P_TTRI超过故障检测的 FD_FAIL_P 时间(默认为 0.3s)。
FD_FAIL_R_TTRI超过故障检测的 FD_FAIL_R 时间(默认为 0.3s)。

外部自动触发系统(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.

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

参数描述
FD_EXT_ATS_EN启用 AUX5 或 MAIN5(取决于飞控板)上的 PWM 输入,以便从外部自动触发系统(ATS)启用故障保护。 默认值:禁用。
FD_EXT_ATS_TRIG来自外部自动触发系统的用于接通故障保护的 PWM 阈值。 默认值:1900m/s。

应急开关

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.

急停开关

A kill switch immediately stops all motor outputs (and if flying, the vehicle will start to fall)! The motors will restart if the switch is reverted within 5 seconds. After 5 seconds the vehicle will automatically disarm; you will need to arm it again in order to start the motors.

解锁/上锁开关

解锁/上锁开关是对默认杆状安全开关机制的_直接替换_(二者作用相同:确保在电机启动/停止之前有一个需要用户留意的步骤)。 它可能优先于默认机制使用,原因如下:

  • 这种机制偏向于切换动作而不是持续运动。
  • 这种机制可以避免因为某种意外误触而引发的飞行期间解锁/上锁。
  • 这种机制没有延迟(立即作出反应)。

The arm/disarm switch immediately disarms (stop) motors for those flight modes that support disarming in flight. 其中包括:

  • 手动模式
  • 特技模式
  • 自稳模式

对于不支持在飞行期间上锁的模式,在飞行期间会忽略该开关信号,但在检测到着陆后可以使用该开关。 不支持飞行期间上锁的模式包括_定点模式_和自主模式(例如_任务模式_、_降落模式_等)。

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.

返航开关

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

其他安全设置

超时自动上锁

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:

参数描述
COM_DISARM_LAND降落后自动上锁的超时时间。
COM_DISARM_PRFLT如果起飞速度太慢,将启动自动上锁。

更多信息