mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_AdvancedFailsafe: make GCS failsafe timeout a parameter
This commit is contained in:
parent
8e08a9bdf6
commit
db72fd16d4
@ -169,6 +169,13 @@ const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = {
|
||||
// @Bitmask: 0: Continue the mission even after comms are recovered (does not go to the mission item at the time comms were lost)
|
||||
// @Bitmask: 1: Enable AFS for all autonomous modes (not just AUTO)
|
||||
AP_GROUPINFO("OPTIONS", 21, AP_AdvancedFailsafe, options, 0),
|
||||
|
||||
// @Param: GCS_TIMEOUT
|
||||
// @DisplayName: GCS timeout
|
||||
// @Description: The time (in seconds) of persistent data link loss before GCS failsafe occurs.
|
||||
// @User: Advanced
|
||||
// @Units: s
|
||||
AP_GROUPINFO("GCS_TIMEOUT", 22, AP_AdvancedFailsafe, _gcs_fail_time_seconds, 10),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
@ -220,7 +227,7 @@ AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms)
|
||||
|
||||
const uint32_t last_heartbeat_ms = gcs().sysid_myggcs_last_seen_time_ms();
|
||||
uint32_t now = AP_HAL::millis();
|
||||
bool gcs_link_ok = ((now - last_heartbeat_ms) < 10000);
|
||||
bool gcs_link_ok = ((now - last_heartbeat_ms) < (_gcs_fail_time_seconds*1000.0f));
|
||||
bool gps_lock_ok = ((now - AP::gps().last_fix_time_ms()) < 3000);
|
||||
|
||||
AP_Mission *_mission = AP::mission();
|
||||
|
@ -126,6 +126,7 @@ protected:
|
||||
AP_Int32 _amsl_limit;
|
||||
AP_Int32 _amsl_margin_gps;
|
||||
AP_Float _rc_fail_time_seconds;
|
||||
AP_Float _gcs_fail_time_seconds;
|
||||
AP_Int8 _max_gps_loss;
|
||||
AP_Int8 _max_comms_loss;
|
||||
AP_Int8 _enable_geofence_fs;
|
||||
|
Loading…
Reference in New Issue
Block a user