mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
GCS_MAVLink: only forward msg once per channel
Issue found and alternative fix provided by Arthur Benemann
This commit is contained in:
parent
6f72d202fe
commit
521f3dc4b9
@ -127,11 +127,13 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl
|
||||
|
||||
// forward on any channels matching the targets
|
||||
bool forwarded = false;
|
||||
bool sent_to_chan[MAVLINK_COMM_NUM_BUFFERS];
|
||||
memset(sent_to_chan, 0, sizeof(sent_to_chan));
|
||||
for (uint8_t i=0; i<num_routes; i++) {
|
||||
if (broadcast_system || (target_system == routes[i].sysid &&
|
||||
(broadcast_component ||
|
||||
target_component == routes[i].compid))) {
|
||||
if (in_channel != routes[i].channel) {
|
||||
if (in_channel != routes[i].channel && !sent_to_chan[routes[i].channel]) {
|
||||
if (comm_get_txspace(routes[i].channel) >=
|
||||
((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES) {
|
||||
#if ROUTING_DEBUG
|
||||
@ -144,6 +146,7 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl
|
||||
#endif
|
||||
_mavlink_resend_uart(routes[i].channel, msg);
|
||||
}
|
||||
sent_to_chan[routes[i].channel] = true;
|
||||
forwarded = true;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user