Copter: use common deferred message handling
This commit is contained in:
parent
8da72fccba
commit
e4b3323455
@ -138,7 +138,7 @@ static NOINLINE void send_limits_status(mavlink_channel_t chan)
|
||||
#endif
|
||||
|
||||
|
||||
static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t packet_drops)
|
||||
static NOINLINE void send_extended_status1(mavlink_channel_t chan)
|
||||
{
|
||||
uint32_t control_sensors_present;
|
||||
uint32_t control_sensors_enabled;
|
||||
@ -574,7 +574,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, uint16_t packet_drops)
|
||||
bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
||||
{
|
||||
int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
|
||||
@ -601,7 +601,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
|
||||
|
||||
case MSG_EXTENDED_STATUS1:
|
||||
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
||||
send_extended_status1(chan, packet_drops);
|
||||
send_extended_status1(chan);
|
||||
CHECK_PAYLOAD_SIZE(POWER_STATUS);
|
||||
gcs[chan-MAVLINK_COMM_0].send_power_status();
|
||||
break;
|
||||
@ -735,65 +735,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, uint16_t packet_drops)
|
||||
{
|
||||
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],
|
||||
packet_drops)) {
|
||||
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, packet_drops)) {
|
||||
// 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++;
|
||||
}
|
||||
}
|
||||
|
||||
const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = {
|
||||
// @Param: RAW_SENS
|
||||
// @DisplayName: Raw sensor stream rate
|
||||
@ -919,9 +860,6 @@ GCS_MAVLINK::update(void)
|
||||
}
|
||||
}
|
||||
|
||||
// Update packet drops counter
|
||||
packet_drops += status.packet_rx_drop_count;
|
||||
|
||||
// handle receiving commands from GCS
|
||||
if (waypoint_receiving) {
|
||||
uint32_t tnow = millis();
|
||||
@ -1064,14 +1002,6 @@ GCS_MAVLINK::data_stream_send(void)
|
||||
}
|
||||
|
||||
|
||||
|
||||
void
|
||||
GCS_MAVLINK::send_message(enum ap_message id)
|
||||
{
|
||||
mavlink_send_message(chan,id, packet_drops);
|
||||
}
|
||||
|
||||
|
||||
void GCS_MAVLINK::handle_guided_request(AP_Mission::Mission_Command &cmd)
|
||||
{
|
||||
do_guided(cmd);
|
||||
@ -1560,11 +1490,11 @@ void gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
||||
hal.util->vsnprintf_P((char *)gcs[0].pending_status.text,
|
||||
sizeof(gcs[0].pending_status.text), fmt, arg_list);
|
||||
va_end(arg_list);
|
||||
mavlink_send_message(MAVLINK_COMM_0, MSG_STATUSTEXT, 0);
|
||||
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, 0);
|
||||
gcs[i].send_message(MSG_STATUSTEXT);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user