MAVLINK: Forward to private channels if sysid and compid match

If the target system ID and target component ID match a private channel,
it is ok to forward that mavlink traffic.  Any traffic without a
matching sysid or compid will not be forwarded on the channel
This commit is contained in:
Matt 2018-11-26 20:55:29 -05:00 committed by Andrew Tridgell
parent ffeeedb0aa
commit adf78ab8d3

View File

@ -139,13 +139,21 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl
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++) {
// Skip if channel is private and the target system or component IDs do not match
if ((GCS_MAVLINK::is_private(routes[i].channel)) &&
(target_system != routes[i].sysid ||
target_component != routes[i].compid)) {
continue;
}
if (broadcast_system || (target_system == routes[i].sysid &&
(broadcast_component ||
target_component == routes[i].compid ||
!match_system))) {
if (in_channel != routes[i].channel &&
!sent_to_chan[routes[i].channel] &&
!GCS_MAVLINK::is_private(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) +
GCS_MAVLINK::packet_overhead_chan(routes[i].channel)) {
#if ROUTING_DEBUG
@ -163,6 +171,7 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl
}
}
}
if (!forwarded && match_system) {
process_locally = true;
}