mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
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:
parent
5a2b26f931
commit
d79302c366
@ -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())) {
|
||||
|
||||
@ -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
|
||||
};
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user