mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
Plane: make the defaut for FS_GCS_ENABL clearer
This commit is contained in:
parent
263f3b116b
commit
ce773f085a
@ -443,7 +443,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Description: Enable ground control station telemetry failsafe. Failsafe will trigger after FS_LONG_TIMEOUT seconds of no MAVLink heartbeat messages. There are two possible enabled settings. Seeing FS_GCS_ENABL to 1 means that GCS failsafe will be triggered when the aircraft has not received a MAVLink HEARTBEAT message. Setting FS_GCS_ENABL to 2 means that GCS failsafe will be triggerded on either a loss of HEARTBEAT messages, or a RADIO_STATUS message from a MAVLink enabled 3DR radio indicating that the ground station is not receiving status updates from the aircraft, which is indicated by the RADIO_STATUS.remrssi field being zero (this may happen if you have a one way link due to asymmetric noise on the ground station and aircraft radios). WARNING: Enabling this option opens up the possibility of your plane going into failsafe mode and running the motor on the ground it it loses contact with your ground station. If this option is enabled on an electric plane then you should enable ARMING_REQUIRED.
|
// @Description: Enable ground control station telemetry failsafe. Failsafe will trigger after FS_LONG_TIMEOUT seconds of no MAVLink heartbeat messages. There are two possible enabled settings. Seeing FS_GCS_ENABL to 1 means that GCS failsafe will be triggered when the aircraft has not received a MAVLink HEARTBEAT message. Setting FS_GCS_ENABL to 2 means that GCS failsafe will be triggerded on either a loss of HEARTBEAT messages, or a RADIO_STATUS message from a MAVLink enabled 3DR radio indicating that the ground station is not receiving status updates from the aircraft, which is indicated by the RADIO_STATUS.remrssi field being zero (this may happen if you have a one way link due to asymmetric noise on the ground station and aircraft radios). WARNING: Enabling this option opens up the possibility of your plane going into failsafe mode and running the motor on the ground it it loses contact with your ground station. If this option is enabled on an electric plane then you should enable ARMING_REQUIRED.
|
||||||
// @Values: 0:Disabled,1:Heartbeat,2:HeartbeatAndREMRSSI
|
// @Values: 0:Disabled,1:Heartbeat,2:HeartbeatAndREMRSSI
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(gcs_heartbeat_fs_enabled, "FS_GCS_ENABL", GCS_HEARTBEAT_FAILSAFE),
|
GSCALAR(gcs_heartbeat_fs_enabled, "FS_GCS_ENABL", GCS_FAILSAFE_OFF),
|
||||||
|
|
||||||
// @Param: FLTMODE_CH
|
// @Param: FLTMODE_CH
|
||||||
// @DisplayName: Flightmode channel
|
// @DisplayName: Flightmode channel
|
||||||
|
@ -260,8 +260,6 @@
|
|||||||
// THROTTLE_FS_VALUE
|
// THROTTLE_FS_VALUE
|
||||||
// SHORT_FAILSAFE_ACTION
|
// SHORT_FAILSAFE_ACTION
|
||||||
// LONG_FAILSAFE_ACTION
|
// LONG_FAILSAFE_ACTION
|
||||||
// GCS_HEARTBEAT_FAILSAFE
|
|
||||||
//
|
|
||||||
#ifndef THROTTLE_FAILSAFE
|
#ifndef THROTTLE_FAILSAFE
|
||||||
# define THROTTLE_FAILSAFE ENABLED
|
# define THROTTLE_FAILSAFE ENABLED
|
||||||
#endif
|
#endif
|
||||||
@ -274,10 +272,6 @@
|
|||||||
#ifndef LONG_FAILSAFE_ACTION
|
#ifndef LONG_FAILSAFE_ACTION
|
||||||
# define LONG_FAILSAFE_ACTION 0
|
# define LONG_FAILSAFE_ACTION 0
|
||||||
#endif
|
#endif
|
||||||
#ifndef GCS_HEARTBEAT_FAILSAFE
|
|
||||||
# define GCS_HEARTBEAT_FAILSAFE DISABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// AUTO_TRIM
|
// AUTO_TRIM
|
||||||
|
Loading…
Reference in New Issue
Block a user