mavlink_parameters: throttle MAVLink param transmission on low-bandwidth links (#25126)

* mavlink_parameters: throttle MAVLink param transmission if in low-bandwidth mode

* mavlink_parameters: simplify param transmission throttling

---------

Co-authored-by: Matthias Grob <maetugr@gmail.com>
This commit is contained in:
Stefano Colli 2025-07-08 13:48:23 +02:00 committed by GitHub
parent 5a2b26f931
commit d79302c366
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
2 changed files with 10 additions and 0 deletions

View File

@ -408,6 +408,14 @@ MavlinkParametersManager::send_untransmitted()
bool
MavlinkParametersManager::send_one()
{
const hrt_abstime now = hrt_absolute_time();
// If in low-bandwidth mode, throttle parameter transmission to 8 Hz
if (_mavlink.get_mode() == Mavlink::MAVLINK_MODE_LOW_BANDWIDTH
&& now < _last_param_sent_timestamp + 125_ms) {
return false;
}
if (_send_all_index >= 0) {
/* send all parameters if requested, but only after the system has booted */
@ -445,6 +453,7 @@ MavlinkParametersManager::send_one()
if (p != PARAM_INVALID) {
send_param(p);
_last_param_sent_timestamp = now;
}
if ((p == PARAM_INVALID) || (_send_all_index >= (int) param_count())) {

View File

@ -162,4 +162,5 @@ protected:
Mavlink &_mavlink;
bool _first_send{false};
hrt_abstime _last_param_sent_timestamp{0}; // time at which the last parameter was sent
};