-
Notifications
You must be signed in to change notification settings - Fork 1.7k
Closed
Description
Mavlink RC command have been implemented recently: #6738 👏
It allows to use single UART for RC and telemetry ✔️
Unfortunately RC_CHANNELS_OVERRIDE can not be sent with rate comparable to SBUS because incoming telemetry messages affect outgoing telemetry rate ❌
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:
- Remove incomingRequestServed flag completely.
- Add a setting mavlink_half_duplex default true. If set to false, incomingRequestServed will be disabled.
- let RC_CHANNELS_OVERRIDE not affect incomingRequestServed flag.
Which solution would be appropriate?
Metadata
Metadata
Assignees
Labels
No labels