|
|
|
@ -6,9 +6,6 @@
@@ -6,9 +6,6 @@
|
|
|
|
|
// use this to prevent recursion during sensor init |
|
|
|
|
static bool in_mavlink_delay; |
|
|
|
|
|
|
|
|
|
// true when we have received at least 1 MAVLink packet |
|
|
|
|
static bool mavlink_active; |
|
|
|
|
|
|
|
|
|
// true if we are out of time in our event timeslice |
|
|
|
|
static bool gcs_out_of_time; |
|
|
|
|
|
|
|
|
@ -790,66 +787,6 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = {
@@ -790,66 +787,6 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = {
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void |
|
|
|
|
GCS_MAVLINK::update(void) |
|
|
|
|
{ |
|
|
|
|
// receive new packets |
|
|
|
|
mavlink_message_t msg; |
|
|
|
|
mavlink_status_t status; |
|
|
|
|
status.packet_rx_drop_count = 0; |
|
|
|
|
|
|
|
|
|
// process received bytes |
|
|
|
|
uint16_t nbytes = comm_get_available(chan); |
|
|
|
|
for (uint16_t i=0; i<nbytes; i++) |
|
|
|
|
{ |
|
|
|
|
uint8_t c = comm_receive_ch(chan); |
|
|
|
|
|
|
|
|
|
#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 && |
|
|
|
|
comm_is_idle(chan)) { |
|
|
|
|
if (c == '\n' || c == '\r') { |
|
|
|
|
crlf_count++; |
|
|
|
|
} else { |
|
|
|
|
crlf_count = 0; |
|
|
|
|
} |
|
|
|
|
if (crlf_count == 3) { |
|
|
|
|
run_cli(_port); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// Try to get a new message |
|
|
|
|
if (mavlink_parse_char(chan, c, &msg, &status)) { |
|
|
|
|
// 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; |
|
|
|
|
} |
|
|
|
|
handleMessage(&msg); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!waypoint_receiving) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
uint32_t tnow = millis(); |
|
|
|
|
|
|
|
|
|
if (waypoint_receiving && |
|
|
|
|
waypoint_request_i <= waypoint_request_last && |
|
|
|
|
tnow > waypoint_timelast_request + 500 + (stream_slowdown*20)) { |
|
|
|
|
waypoint_timelast_request = tnow; |
|
|
|
|
send_message(MSG_NEXT_WAYPOINT); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// stop waypoint receiving if timeout |
|
|
|
|
if (waypoint_receiving && (millis() - waypoint_timelast_receive) > waypoint_receive_timeout){ |
|
|
|
|
waypoint_receiving = false; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// see if we should send a stream now. Called at 50Hz |
|
|
|
|
bool GCS_MAVLINK::stream_trigger(enum streams stream_num) |
|
|
|
|
{ |
|
|
|
@ -1441,7 +1378,11 @@ static void gcs_update(void)
@@ -1441,7 +1378,11 @@ static void gcs_update(void)
|
|
|
|
|
{ |
|
|
|
|
for (uint8_t i=0; i<num_gcs; i++) { |
|
|
|
|
if (gcs[i].initialised) { |
|
|
|
|
gcs[i].update(); |
|
|
|
|
#if CLI_ENABLED == ENABLED |
|
|
|
|
gcs[i].update(run_cli); |
|
|
|
|
#else |
|
|
|
|
gcs[i].update(NULL); |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|