Browse Source

Copter: only allow CLI within 20s of startup and when motors not armed

mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
ce8313e8fb
  1. 2
      ArduCopter/GCS_Mavlink.pde

2
ArduCopter/GCS_Mavlink.pde

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

Loading…
Cancel
Save