GCS_MAVLink: use RADIO_STATUS message txbuf field

this avoids overrunning radio buffer in queued_param_send()
This commit is contained in:
Brad Bosch 2020-12-14 18:26:03 -06:00 committed by Andrew Tridgell
parent 4346264113
commit a2192eda5e
3 changed files with 6 additions and 1 deletions

View File

@ -334,6 +334,7 @@ public:
virtual uint64_t capabilities() const; virtual uint64_t capabilities() const;
uint16_t get_stream_slowdown_ms() const { return stream_slowdown_ms; } uint16_t get_stream_slowdown_ms() const { return stream_slowdown_ms; }
uint8_t get_last_txbuf() const { return last_txbuf; }
MAV_RESULT set_message_interval(uint32_t msg_id, int32_t interval_us); MAV_RESULT set_message_interval(uint32_t msg_id, int32_t interval_us);
@ -571,6 +572,8 @@ private:
// number of extra ms to add to slow things down for the radio // number of extra ms to add to slow things down for the radio
uint16_t stream_slowdown_ms; uint16_t stream_slowdown_ms;
// last reported radio buffer percent available
uint8_t last_txbuf = 100;
// perf counters // perf counters
AP_HAL::Util::perf_counter_t _perf_packet; AP_HAL::Util::perf_counter_t _perf_packet;

View File

@ -650,6 +650,8 @@ void GCS_MAVLINK::handle_radio_status(const mavlink_message_t &msg, bool log_rad
last_radio_status.remrssi_ms = now; last_radio_status.remrssi_ms = now;
} }
last_txbuf = packet.txbuf;
// use the state of the transmit buffer in the radio to // use the state of the transmit buffer in the radio to
// control the stream rate, giving us adaptive software // control the stream rate, giving us adaptive software
// flow control // flow control

View File

@ -71,7 +71,7 @@ GCS_MAVLINK::queued_param_send()
} }
count -= async_replies_sent_count; count -= async_replies_sent_count;
while (count && _queued_parameter != nullptr) { while (count && _queued_parameter != nullptr && get_last_txbuf() > 50) {
char param_name[AP_MAX_NAME_SIZE]; char param_name[AP_MAX_NAME_SIZE];
_queued_parameter->copy_name_token(_queued_parameter_token, param_name, sizeof(param_name), true); _queued_parameter->copy_name_token(_queued_parameter_token, param_name, sizeof(param_name), true);