Browse Source

GCS_MAVLink: don't route RADIO and RADIO_STATUS packets

they don't mean anything off the local link
mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
b855c70139
  1. 6
      libraries/GCS_MAVLink/MAVLink_routing.cpp

6
libraries/GCS_MAVLink/MAVLink_routing.cpp

@ -102,6 +102,12 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl
// learn new routes // learn new routes
learn_route(in_channel, msg); 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) { if (msg->msgid == MAVLINK_MSG_ID_HEARTBEAT) {
// heartbeat needs special handling // heartbeat needs special handling
handle_heartbeat(in_channel, msg); handle_heartbeat(in_channel, msg);

Loading…
Cancel
Save