mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Plane: use common deferred message handling
This commit is contained in:
parent
0832aba6bc
commit
4031f7d368
@ -617,7 +617,7 @@ static bool telemetry_delayed(mavlink_channel_t chan)
|
||||
|
||||
|
||||
// try to send a message, return false if it won't fit in the serial tx buffer
|
||||
static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id)
|
||||
bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
||||
{
|
||||
int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
|
||||
@ -781,64 +781,6 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id)
|
||||
}
|
||||
|
||||
|
||||
#define MAX_DEFERRED_MESSAGES MSG_RETRY_DEFERRED
|
||||
static struct mavlink_queue {
|
||||
enum ap_message deferred_messages[MAX_DEFERRED_MESSAGES];
|
||||
uint8_t next_deferred_message;
|
||||
uint8_t num_deferred_messages;
|
||||
} mavlink_queue[MAVLINK_COMM_NUM_BUFFERS];
|
||||
|
||||
// send a message using mavlink
|
||||
static void mavlink_send_message(mavlink_channel_t chan, enum ap_message id)
|
||||
{
|
||||
uint8_t i, nextid;
|
||||
struct mavlink_queue *q = &mavlink_queue[(uint8_t)chan];
|
||||
|
||||
// see if we can send the deferred messages, if any
|
||||
while (q->num_deferred_messages != 0) {
|
||||
if (!mavlink_try_send_message(chan,
|
||||
q->deferred_messages[q->next_deferred_message])) {
|
||||
break;
|
||||
}
|
||||
q->next_deferred_message++;
|
||||
if (q->next_deferred_message == MAX_DEFERRED_MESSAGES) {
|
||||
q->next_deferred_message = 0;
|
||||
}
|
||||
q->num_deferred_messages--;
|
||||
}
|
||||
|
||||
if (id == MSG_RETRY_DEFERRED) {
|
||||
return;
|
||||
}
|
||||
|
||||
// this message id might already be deferred
|
||||
for (i=0, nextid = q->next_deferred_message; i < q->num_deferred_messages; i++) {
|
||||
if (q->deferred_messages[nextid] == id) {
|
||||
// its already deferred, discard
|
||||
return;
|
||||
}
|
||||
nextid++;
|
||||
if (nextid == MAX_DEFERRED_MESSAGES) {
|
||||
nextid = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if (q->num_deferred_messages != 0 ||
|
||||
!mavlink_try_send_message(chan, id)) {
|
||||
// can't send it now, so defer it
|
||||
if (q->num_deferred_messages == MAX_DEFERRED_MESSAGES) {
|
||||
// the defer buffer is full, discard
|
||||
return;
|
||||
}
|
||||
nextid = q->next_deferred_message + q->num_deferred_messages;
|
||||
if (nextid >= MAX_DEFERRED_MESSAGES) {
|
||||
nextid -= MAX_DEFERRED_MESSAGES;
|
||||
}
|
||||
q->deferred_messages[nextid] = id;
|
||||
q->num_deferred_messages++;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
default stream rates to 1Hz
|
||||
*/
|
||||
@ -1119,14 +1061,6 @@ GCS_MAVLINK::data_stream_send(void)
|
||||
}
|
||||
|
||||
|
||||
|
||||
void
|
||||
GCS_MAVLINK::send_message(enum ap_message id)
|
||||
{
|
||||
mavlink_send_message(chan, id);
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
handle a request to switch to guided mode. This happens via a
|
||||
callback from handle_mission_item()
|
||||
@ -1799,11 +1733,11 @@ void gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
DataFlash.Log_Write_Message(gcs[0].pending_status.text);
|
||||
#endif
|
||||
mavlink_send_message(MAVLINK_COMM_0, MSG_STATUSTEXT);
|
||||
gcs[0].send_message(MSG_STATUSTEXT);
|
||||
for (uint8_t i=1; i<num_gcs; i++) {
|
||||
if (gcs[i].initialised) {
|
||||
gcs[i].pending_status = gcs[0].pending_status;
|
||||
mavlink_send_message((mavlink_channel_t)i, MSG_STATUSTEXT);
|
||||
gcs[i].send_message(MSG_STATUSTEXT);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user