|
|
|
@ -23,7 +23,7 @@
@@ -23,7 +23,7 @@
|
|
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
|
|
|
|
|
|
uint32_t GCS_MAVLINK::last_radio_status_remrssi_ms; |
|
|
|
|
bool GCS_MAVLINK::mavlink_active = false; |
|
|
|
|
uint8_t GCS_MAVLINK::mavlink_active = 0; |
|
|
|
|
|
|
|
|
|
GCS_MAVLINK::GCS_MAVLINK() : |
|
|
|
|
waypoint_receive_timeout(5000) |
|
|
|
@ -871,7 +871,7 @@ GCS_MAVLINK::update(void (*run_cli)(AP_HAL::UARTDriver *))
@@ -871,7 +871,7 @@ GCS_MAVLINK::update(void (*run_cli)(AP_HAL::UARTDriver *))
|
|
|
|
|
if (run_cli != NULL) { |
|
|
|
|
/* allow CLI to be started by hitting enter 3 times, if no
|
|
|
|
|
* heartbeat packets have been received */ |
|
|
|
|
if (!mavlink_active && (hal.scheduler->millis() - _cli_timeout) < 20000 &&
|
|
|
|
|
if ((mavlink_active==0) && (hal.scheduler->millis() - _cli_timeout) < 20000 &&
|
|
|
|
|
comm_is_idle(chan)) { |
|
|
|
|
if (c == '\n' || c == '\r') { |
|
|
|
|
crlf_count++; |
|
|
|
@ -889,7 +889,7 @@ GCS_MAVLINK::update(void (*run_cli)(AP_HAL::UARTDriver *))
@@ -889,7 +889,7 @@ GCS_MAVLINK::update(void (*run_cli)(AP_HAL::UARTDriver *))
|
|
|
|
|
// we exclude radio packets to make it possible to use the
|
|
|
|
|
// CLI over the radio
|
|
|
|
|
if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) { |
|
|
|
|
mavlink_active = true; |
|
|
|
|
mavlink_active |= (1U<<chan); |
|
|
|
|
} |
|
|
|
|
handleMessage(&msg); |
|
|
|
|
} |
|
|
|
|