mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Copter: Change the process description
This commit is contained in:
parent
77acf9bcc2
commit
9d1c3a2df0
@ -114,7 +114,7 @@ void Copter::read_radio()
|
|||||||
}
|
}
|
||||||
|
|
||||||
const uint32_t elapsed = tnow_ms - last_radio_update_ms;
|
const uint32_t elapsed = tnow_ms - last_radio_update_ms;
|
||||||
// turn on throttle failsafe if no update from the RC Radio for 500ms or 2000ms if we are using RC_OVERRIDE
|
// turn on throttle failsafe if no update from the RC Radio for 500ms or 1000ms if we are using RC_OVERRIDE
|
||||||
const uint32_t timeout = RC_Channels::has_active_overrides() ? FS_RADIO_RC_OVERRIDE_TIMEOUT_MS : FS_RADIO_TIMEOUT_MS;
|
const uint32_t timeout = RC_Channels::has_active_overrides() ? FS_RADIO_RC_OVERRIDE_TIMEOUT_MS : FS_RADIO_TIMEOUT_MS;
|
||||||
if (elapsed < timeout) {
|
if (elapsed < timeout) {
|
||||||
// not timed out yet
|
// not timed out yet
|
||||||
|
Loading…
Reference in New Issue
Block a user