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:
Andrew Tridgell 2011-12-16 19:44:37 +11:00
parent 9e9b229a1d
commit e1e9002fad

View File

@ -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 {