Copter: 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:56:02 +11:00
parent 7e58bde826
commit d22a7c64c9

View File

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