Rover: only enter CLI is link is idle when 3 enters are hit

this will prevent binary contents of RADIO packets being interpreted
as CLI enter line-feeds
This commit is contained in:
Andrew Tridgell 2013-03-21 21:58:12 +11:00
parent 6948e0c473
commit 24094252fd
1 changed files with 2 additions and 1 deletions

View File

@ -733,7 +733,8 @@ 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 && (millis() - _cli_timeout) < 20000) {
if (mavlink_active == 0 && (millis() - _cli_timeout) < 20000 &&
comm_is_idle(chan)) {
if (c == '\n' || c == '\r') {
crlf_count++;
} else {