Browse Source

GCS_MAVLink: clarify packetReceive calling handlemessage checks

modules/libcanard/
mission-4.1.18
Peter Barker 6 years ago committed by Peter Barker
parent
commit
91c8d0b915
  1. 11
      libraries/GCS_MAVLink/GCS_Common.cpp

11
libraries/GCS_MAVLink/GCS_Common.cpp

@ -1427,10 +1427,15 @@ void GCS_MAVLINK::packetReceived(const mavlink_status_t &status, @@ -1427,10 +1427,15 @@ void GCS_MAVLINK::packetReceived(const mavlink_status_t &status,
cstatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
}
}
if (routing.check_and_forward(chan, &msg) &&
accept_packet(status, msg)) {
handleMessage(&msg);
if (!routing.check_and_forward(chan, &msg)) {
// the routing code has indicated we should not handle this packet locally
return;
}
if (!accept_packet(status, msg)) {
// e.g. enforce-sysid says we shouldn't look at this packet
return;
}
handleMessage(&msg);
}
void

Loading…
Cancel
Save