1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 09:45:33 +03:00

Improve MAVLink behavior with half-duplex links, update default SRs

This commit is contained in:
MUSTARDTIGERFPV 2024-07-11 20:19:47 +00:00
parent ff94b7702e
commit 92d6315e59
3 changed files with 16 additions and 11 deletions

View file

@ -2518,7 +2518,7 @@ Rate of the extra1 message for MAVLink telemetry
| Default | Min | Max | | Default | Min | Max |
| --- | --- | --- | | --- | --- | --- |
| 10 | 0 | 255 | | 2 | 0 | 255 |
--- ---
@ -2558,7 +2558,7 @@ Rate of the RC channels message for MAVLink telemetry
| Default | Min | Max | | Default | Min | Max |
| --- | --- | --- | | --- | --- | --- |
| 5 | 0 | 255 | | 1 | 0 | 255 |
--- ---

View file

@ -3155,7 +3155,7 @@ groups:
type: uint8_t type: uint8_t
min: 0 min: 0
max: 255 max: 255
default_value: 5 default_value: 1
- name: mavlink_pos_rate - name: mavlink_pos_rate
description: "Rate of the position message for MAVLink telemetry" description: "Rate of the position message for MAVLink telemetry"
field: mavlink.position_rate field: mavlink.position_rate
@ -3169,7 +3169,7 @@ groups:
type: uint8_t type: uint8_t
min: 0 min: 0
max: 255 max: 255
default_value: 10 default_value: 2
- name: mavlink_extra2_rate - name: mavlink_extra2_rate
description: "Rate of the extra2 message for MAVLink telemetry" description: "Rate of the extra2 message for MAVLink telemetry"
field: mavlink.extra2_rate field: mavlink.extra2_rate

View file

@ -1222,6 +1222,11 @@ static bool processMAVLinkIncomingTelemetry(void)
return false; return false;
} }
static bool isMAVLinkTelemetryHalfDuplex(void) {
return telemetryConfig()->halfDuplex ||
(rxConfig()->receiverType == RX_TYPE_SERIAL && rxConfig()->serialrx_provider == SERIALRX_MAVLINK && tristateWithDefaultOffIsActive(rxConfig()->halfDuplex));
}
void handleMAVLinkTelemetry(timeUs_t currentTimeUs) void handleMAVLinkTelemetry(timeUs_t currentTimeUs)
{ {
if (!mavlinkTelemetryEnabled) { if (!mavlinkTelemetryEnabled) {
@ -1232,18 +1237,18 @@ void handleMAVLinkTelemetry(timeUs_t currentTimeUs)
return; return;
} }
// Process incoming MAVLink - ignore the return indicating whether or not a message was processed // Process incoming MAVLink
// Very few telemetry links are dynamic uplink/downlink split so uplink telemetry shouldn't reduce downlink bandwidth availability bool receivedMessage = processMAVLinkIncomingTelemetry();
processMAVLinkIncomingTelemetry();
// Determine whether to send telemetry back
bool shouldSendTelemetry = false; bool shouldSendTelemetry = false;
// Determine whether to send telemetry back based on flow control / pacing
if (txbuff_valid) { if (txbuff_valid) {
// Use flow control if available // Use flow control if available
shouldSendTelemetry = txbuff_free >= 33; shouldSendTelemetry = txbuff_free >= 33;
} else { } else {
// If not, use blind frame pacing // If not, use blind frame pacing - and back off for collision avoidance if half-duplex
shouldSendTelemetry = (currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY; bool halfDuplexBackoff = (isMAVLinkTelemetryHalfDuplex() && receivedMessage);
shouldSendTelemetry = ((currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY) && !halfDuplexBackoff;
} }
if (shouldSendTelemetry) { if (shouldSendTelemetry) {