mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 04:33:10 +08:00
docs: clarify RC termination switch behavior
This commit is contained in:
committed by
Matthias Grob
parent
6c5c88f72e
commit
a5f92a4615
@@ -1,6 +1,6 @@
|
||||
# Flight Termination Configuration
|
||||
|
||||
The _Flight termination_ [failsafe action](../config/safety.md#failsafe-actions) may be triggered by a [safety check](../config/safety.md) (e.g. RC Loss, geofence violation, etc. on any vehicle type or in any flight mode), or by the [Failure Detector](../config/safety.md#failure-detector).
|
||||
The _Flight termination_ [failsafe action](../config/safety.md#failsafe-actions) may be triggered by a [safety check](../config/safety.md) (e.g. RC Loss, geofence violation, etc. on any vehicle type or in any flight mode), by the [Failure Detector](../config/safety.md#failure-detector), or manually by toggling a termination switch mapped to an RC channel (see [RC_MAP_TERM_SW](../advanced_config/parameter_reference.md#RC_MAP_TERM_SW)).
|
||||
|
||||
::: info
|
||||
Flight termination may also be triggered from a ground station or companion computer using the MAVLink [MAV_CMD_DO_FLIGHTTERMINATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_FLIGHTTERMINATION) command.
|
||||
|
||||
@@ -1442,7 +1442,13 @@ PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
|
||||
PARAM_DEFINE_INT32(RC_MAP_KILL_SW, 0);
|
||||
|
||||
/**
|
||||
* Termination switch channel
|
||||
* Termination switch channel.
|
||||
*
|
||||
* Use this channel to trigger flight termination. When flight termination is activated,
|
||||
* PX4 disables all controllers and sets all PWM outputs to their failsafe values.
|
||||
*
|
||||
* Note: Flight termination is irreversible—once triggered, it cannot be undone.
|
||||
* This is unlike a kill switch, which can be toggled back. Use with caution.
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
|
||||
Reference in New Issue
Block a user