mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
only check for "enter 3 times" in first 20s after boot
we don't want stray bytes on serial3 to make us enter the CLI during flight!
This commit is contained in:
parent
9e9b229a1d
commit
e1e9002fad
@ -751,7 +751,7 @@ GCS_MAVLINK::update(void)
|
||||
#if CLI_ENABLED == ENABLED
|
||||
/* allow CLI to be started by hitting enter 3 times, if no
|
||||
heartbeat packets have been received */
|
||||
if (mavlink_active == 0) {
|
||||
if (mavlink_active == 0 && millis() < 20000) {
|
||||
if (c == '\n' || c == '\r') {
|
||||
crlf_count++;
|
||||
} else {
|
||||
|
Loading…
Reference in New Issue
Block a user