From 521f3dc4b9c380a0e160f81ba794fea57dd497cb Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 21 Jul 2015 20:49:20 +0900 Subject: [PATCH] GCS_MAVLink: only forward msg once per channel Issue found and alternative fix provided by Arthur Benemann --- libraries/GCS_MAVLink/MAVLink_routing.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/MAVLink_routing.cpp b/libraries/GCS_MAVLink/MAVLink_routing.cpp index 17bf45294a..56548b658b 100644 --- a/libraries/GCS_MAVLink/MAVLink_routing.cpp +++ b/libraries/GCS_MAVLink/MAVLink_routing.cpp @@ -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= ((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; } }