Browse Source

GCS_MAVLink: Don't forward MAVLink data on channels marked private, make private channels more private

zr-v5.1
Michael du Breuil 5 years ago committed by Peter Barker
parent
commit
6773821b3b
  1. 4
      libraries/GCS_MAVLink/GCS_Common.cpp
  2. 5
      libraries/GCS_MAVLink/MAVLink_routing.cpp

4
libraries/GCS_MAVLink/GCS_Common.cpp

@ -108,6 +108,10 @@ bool GCS_MAVLINK::init(uint8_t instance) @@ -108,6 +108,10 @@ bool GCS_MAVLINK::init(uint8_t instance)
return false;
}
if (!serial_manager.should_forward_mavlink_telemetry(protocol, instance)) {
set_channel_private(chan);
}
/*
Now try to cope with SiK radios that may be stuck in bootloader
mode because CTS was held while powering on. This tells the

5
libraries/GCS_MAVLink/MAVLink_routing.cpp

@ -97,6 +97,11 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl @@ -97,6 +97,11 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl
return true;
}
// don't ever forward data from a private channel
if ((GCS_MAVLINK::is_private(in_channel))) {
return true;
}
// learn new routes
learn_route(in_channel, msg);

Loading…
Cancel
Save