mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: Change Radio Failsafe Timeout
Change Radio Failsafe Timeout from 2 seconds to 200ms
This commit is contained in:
parent
3c9c943b67
commit
07d43534c1
@ -317,9 +317,14 @@
|
||||
# define FS_GCS_TIMEOUT_MS 5000 // gcs failsafe triggers after 5 seconds with no GCS heartbeat
|
||||
#endif
|
||||
|
||||
// Radio failsafe while using RC_override
|
||||
#ifndef FS_RADIO_RC_OVERRIDE_TIMEOUT_MS
|
||||
# define FS_RADIO_RC_OVERRIDE_TIMEOUT_MS 2000 // RC Radio failsafe triggers after 2 seconds while using RC_override from ground station
|
||||
#endif
|
||||
|
||||
// Radio failsafe
|
||||
#ifndef FAILSAFE_RADIO_TIMEOUT_MS
|
||||
#define FAILSAFE_RADIO_TIMEOUT_MS 200 // RC Radio Failsafe triggers after 200 miliseconds with No RC Input
|
||||
#ifndef FS_RADIO_TIMEOUT_MS
|
||||
#define FS_RADIO_TIMEOUT_MS 500 // RC Radio Failsafe triggers after 500 miliseconds with No RC Input
|
||||
#endif
|
||||
|
||||
// possible values for FS_GCS parameter
|
||||
|
@ -123,11 +123,11 @@ static void read_radio()
|
||||
RC_Channel_aux::output_ch_all();
|
||||
}else{
|
||||
uint32_t elapsed = millis() - last_update;
|
||||
// turn on throttle failsafe if no update from ppm encoder for 2 seconds
|
||||
if ((ap.rc_receiver_present && (elapsed >= FAILSAFE_RADIO_TIMEOUT_MS)) || (!ap.rc_receiver_present && (elapsed >= FS_GCS_TIMEOUT_MS))
|
||||
&& g.failsafe_throttle && motors.armed() && !failsafe.radio) {
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_RADIO, ERROR_CODE_RADIO_LATE_FRAME);
|
||||
set_failsafe_radio(true);
|
||||
// turn on throttle failsafe if no update from the RC Radio for 500ms or 2000ms if we are using RC_OVERRIDE
|
||||
if ((!failsafe.rc_override_active && (elapsed >= FS_RADIO_TIMEOUT_MS)) || (failsafe.rc_override_active && (elapsed >= FS_RADIO_RC_OVERRIDE_TIMEOUT_MS))
|
||||
&& g.failsafe_throttle && motors.armed() && !failsafe.radio) {
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_RADIO, ERROR_CODE_RADIO_LATE_FRAME);
|
||||
set_failsafe_radio(true);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user