GCS_MAVLink: don't route RADIO and RADIO_STATUS packets

they don't mean anything off the local link
This commit is contained in:
Andrew Tridgell 2016-05-31 22:13:05 +10:00
parent cfaacf031b
commit b855c70139

View File

@ -102,6 +102,12 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl
// learn new routes
learn_route(in_channel, msg);
if (msg->msgid == MAVLINK_MSG_ID_RADIO ||
msg->msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
// don't forward RADIO packets
return true;
}
if (msg->msgid == MAVLINK_MSG_ID_HEARTBEAT) {
// heartbeat needs special handling
handle_heartbeat(in_channel, msg);