diff --git a/src/boards/Payload/Radio/MessageHandler.cpp b/src/boards/Payload/Radio/MessageHandler.cpp index 02ad09f4ef039662dbda52fba3d855b454d046f7..43166cfbaf6159af035b1628a669d3e985c06e73 100644 --- a/src/boards/Payload/Radio/MessageHandler.cpp +++ b/src/boards/Payload/Radio/MessageHandler.cpp @@ -287,7 +287,7 @@ void Radio::MavlinkBackend::handleMessage(const mavlink_message_t& msg) { parent.getModule<Sensors>()->resetBaroCalibrationReference(); EventBroker::getInstance().post(TMTC_CALIBRATE, TOPIC_TMTC); - enqueueAck(msg); + return enqueueAck(msg); } else { @@ -296,11 +296,11 @@ void Radio::MavlinkBackend::handleMessage(const mavlink_message_t& msg) if (press < 50000) { - enqueueWack(msg); + return enqueueWack(msg); } else { - enqueueAck(msg); + return enqueueAck(msg); } } }