Browse Source

GCS_MAVLink: only call message handler for our own messages

master
Andrew Tridgell 10 years ago committed by Randy Mackay
parent
commit
aa88ba4158
  1. 2
      libraries/GCS_MAVLink/GCS_Common.cpp

2
libraries/GCS_MAVLink/GCS_Common.cpp

@ -908,9 +908,11 @@ GCS_MAVLINK::update(void (*run_cli)(AP_HAL::UARTDriver *)) @@ -908,9 +908,11 @@ GCS_MAVLINK::update(void (*run_cli)(AP_HAL::UARTDriver *))
if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) {
mavlink_active |= (1U<<chan);
}
if (!routing.check_and_forward(chan, &msg)) {
handleMessage(&msg);
}
}
}
if (!waypoint_receiving) {
return;

Loading…
Cancel
Save