inav icon indicating copy to clipboard operation
inav copied to clipboard

Incoming Mavlink telemetry affects outgoing telemetry rate

Open RomanLut opened this issue 3 years ago • 3 comments

Mavlink RC command have been implemented recently: https://github.com/iNavFlight/inav/pull/6738 :clap:

It allows to use single UART for RC and telemetry :heavy_check_mark:

Unfortunately RC_CHANNELS_OVERRIDE can not be sent with rate comparable to SBUS because incoming telemetry messages affect outgoing telemetry rate :x:

At 50 Hz, outgoing telemetry is not emited at all.

telemetry\mavlink.h:

#define TELEMETRY_MAVLINK_MAXRATE       50
#define TELEMETRY_MAVLINK_DELAY         ((1000 * 1000) / TELEMETRY_MAVLINK_MAXRATE)


    // If we did serve data on incoming request - skip next scheduled messages batch to avoid link clogging
    if (processMAVLinkIncomingTelemetry()) {
        incomingRequestServed = true;
    }

    if ((currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY) {
        // Only process scheduled data if we didn't serve any incoming request this cycle
        if (!incomingRequestServed) {
            processMAVLinkTelemetry(currentTimeUs);
        }
        lastMavlinkMessage = currentTimeUs;
        incomingRequestServed = false;
    }

I gues code above was added to support half-duplex links.

I would like to fix this and do a PR, but first I would like to discuss how to handle this problem.

I see the following solutions:

  1. Remove incomingRequestServed flag completely.
  2. Add a setting mavlink_half_duplex default true. If set to false, incomingRequestServed will be disabled.
  3. let RC_CHANNELS_OVERRIDE not affect incomingRequestServed flag.

Which solution would be appropriate?

RomanLut avatar Jun 17 '22 18:06 RomanLut

Ok I rephrase: which pull request will be accepted? 😃

RomanLut avatar Jul 05 '22 11:07 RomanLut

Based on a quick search of github the mavlink_maxrate seems to come from cleanflight and has been carried on since then. Seems like a bit of a hack that worked in the context of it being used for mostly unidirectional telemetry and not being fully utilised in cleanflight.

payor-ma avatar Jul 07 '22 01:07 payor-ma

Ok, there is "Receiver protocol half-duplex" box in configuratior:

image

It can be used to set mavlink protocol half/full duplex if RC protocol is "Mavlink".

RomanLut avatar Jul 31 '22 01:07 RomanLut