diff --git a/ArduCopter/GCS.h b/ArduCopter/GCS.h index bccc0e140474c1f13a865fd348a2a39857d50dc6..d8666d316c70b70159a185f3ee2535dc8cca7ecc 100644 --- a/ArduCopter/GCS.h +++ b/ArduCopter/GCS.h @@ -133,6 +133,8 @@ public: // see if we should send a stream now. Called at 50Hz bool stream_trigger(enum streams stream_num); + // call to reset the timeout window for entering the cli + void reset_cli_timeout(); private: void handleMessage(mavlink_message_t * msg); @@ -204,6 +206,10 @@ private: // number of extra ticks to add to slow things down for the radio uint8_t stream_slowdown; + + // millis value to calculate cli timeout relative to. + // exists so we can separate the cli entry time from the system start time + uint32_t _cli_timeout; }; #endif // __GCS_H diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 44be364e77516d0e20bf259f077cad8c59aadd53..2faa2ea70cd3a0389084870e41e829336d3ee3b4 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -781,6 +781,7 @@ GCS_MAVLINK::init(FastSerial * port) chan = MAVLINK_COMM_1; } _queued_parameter = NULL; + reset_cli_timeout(); } void @@ -799,7 +800,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 == false) { + if (mavlink_active == false && (millis() - _cli_timeout) < 20000 && !motors.armed()) { if (c == '\n' || c == '\r') { crlf_count++; } else { @@ -2045,6 +2046,10 @@ GCS_MAVLINK::queued_waypoint_send() } } +void GCS_MAVLINK::reset_cli_timeout() { + _cli_timeout = millis(); +} + /* * a delay() callback that processes MAVLink packets. We set this as the * callback in long running library initialisation routines to allow diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index 61540c5af0b2200037497539e6a17c3ba6b51b55..b159cb47751e454ce460715c6a9ab4605b0943ed 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -8,6 +8,7 @@ Improvements over 2.9.1: 4) bug fix for alt_hold being passed as int16_t to get_throttle_althold_with_slew 5) bug fix for throttle after acro flip (was being kept at min throttle if pilot switched out of ACRO mode while inverted) 6) reduce yaw_rate P default to 0.20 (was 0.25) +7) fix to prevent cli from being entered more than 20seconds after reboot ------------------------------------------------------------------ ArduCopter 2.9.1 & 2.9.1-rc2 01-Feb-2013 diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 0655ed20f308292561e87d5d2308eae3ea2ac1ad..8b99b4f09bf9628a8533ebee797fed5d9d3c6820 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -199,6 +199,7 @@ static void init_ardupilot() } else if (DataFlash.NeedErase()) { gcs_send_text_P(SEVERITY_LOW, PSTR("ERASING LOGS")); do_erase_logs(); + gcs0.reset_cli_timeout(); } if (g.log_bitmask != 0) { DataFlash.start_new_log();