Browse Source

Copter: only allow entering the CLI within 30 seconds of start-up

master
Randy Mackay 12 years ago
parent
commit
dcf21eee8f
  1. 6
      ArduCopter/GCS.h
  2. 7
      ArduCopter/GCS_Mavlink.pde
  3. 1
      ArduCopter/system.pde

6
ArduCopter/GCS.h

@ -122,6 +122,8 @@ public: @@ -122,6 +122,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);
@ -192,6 +194,10 @@ private: @@ -192,6 +194,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

7
ArduCopter/GCS_Mavlink.pde

@ -849,6 +849,7 @@ GCS_MAVLINK::init(AP_HAL::UARTDriver* port) @@ -849,6 +849,7 @@ GCS_MAVLINK::init(AP_HAL::UARTDriver* port)
chan = MAVLINK_COMM_1;
}
_queued_parameter = NULL;
reset_cli_timeout();
}
void
@ -867,7 +868,7 @@ GCS_MAVLINK::update(void) @@ -867,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 == false) {
if (mavlink_active == 0 && (millis() - _cli_timeout) < 30000) {
if (c == '\n' || c == '\r') {
crlf_count++;
} else {
@ -2178,6 +2179,10 @@ GCS_MAVLINK::queued_waypoint_send() @@ -2178,6 +2179,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

1
ArduCopter/system.pde

@ -181,6 +181,7 @@ static void init_ardupilot() @@ -181,6 +181,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();

Loading…
Cancel
Save