Browse Source

GCS_MAVLink: reserve some space when param fetch fails

this ensures we give some buffer space for parameter fetch when we are
low on buffer space

we reserve 100 bytes for 2 seconds after a param fetch fails due to
low buffer space
mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
7ec513668e
  1. 3
      libraries/GCS_MAVLink/GCS.h
  2. 9
      libraries/GCS_MAVLink/GCS_Common.cpp
  3. 17
      libraries/GCS_MAVLink/GCS_Signing.cpp

3
libraries/GCS_MAVLink/GCS.h

@ -306,6 +306,9 @@ private: @@ -306,6 +306,9 @@ private:
uint8_t next_deferred_message;
uint8_t num_deferred_messages;
// time when we missed sending a parameter for GCS
static uint32_t reserve_param_space_start_ms;
// bitmask of what mavlink channels are active
static uint8_t mavlink_active;

9
libraries/GCS_MAVLink/GCS_Common.cpp

@ -29,6 +29,7 @@ extern const AP_HAL::HAL& hal; @@ -29,6 +29,7 @@ extern const AP_HAL::HAL& hal;
uint32_t GCS_MAVLINK::last_radio_status_remrssi_ms;
uint8_t GCS_MAVLINK::mavlink_active = 0;
ObjectArray<GCS_MAVLINK::statustext_t> GCS_MAVLINK::_statustext_queue(GCS_MAVLINK_PAYLOAD_STATUS_CAPACITY);
uint32_t GCS_MAVLINK::reserve_param_space_start_ms;
GCS_MAVLINK::GCS_MAVLINK()
{
@ -579,9 +580,17 @@ void GCS_MAVLINK::handle_param_request_read(mavlink_message_t *msg) @@ -579,9 +580,17 @@ void GCS_MAVLINK::handle_param_request_read(mavlink_message_t *msg)
mavlink_param_request_read_t packet;
mavlink_msg_param_request_read_decode(msg, &packet);
/*
we reserve some space for sending parameters if the client ever
fails to get a parameter due to lack of space
*/
uint32_t saved_reserve_param_space_start_ms = reserve_param_space_start_ms;
reserve_param_space_start_ms = 0;
if (!HAVE_PAYLOAD_SPACE(chan, PARAM_VALUE)) {
reserve_param_space_start_ms = AP_HAL::millis();
return;
}
reserve_param_space_start_ms = saved_reserve_param_space_start_ms;
enum ap_var_type p_type;
AP_Param *vp;

17
libraries/GCS_MAVLink/GCS_Signing.cpp

@ -234,10 +234,23 @@ bool GCS_MAVLINK::signing_enabled(void) const @@ -234,10 +234,23 @@ bool GCS_MAVLINK::signing_enabled(void) const
*/
uint8_t GCS_MAVLINK::packet_overhead_chan(mavlink_channel_t chan)
{
/*
reserve 100 bytes for parameters when a GCS fails to fetch a
parameter due to lack of buffer space. The reservation lasts 2
seconds
*/
uint8_t reserved_space = 0;
if (reserve_param_space_start_ms != 0 &&
AP_HAL::millis() - reserve_param_space_start_ms < 2000) {
reserved_space = 100;
} else {
reserve_param_space_start_ms = 0;
}
const mavlink_status_t *status = mavlink_get_channel_status(chan);
if (status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) {
return MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_SIGNATURE_BLOCK_LEN;
return MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_SIGNATURE_BLOCK_LEN + reserved_space;
}
return MAVLINK_NUM_NON_PAYLOAD_BYTES;
return MAVLINK_NUM_NON_PAYLOAD_BYTES + reserved_space;
}

Loading…
Cancel
Save