diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 2dcfe4c9b9..2c807fca05 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -530,6 +530,9 @@ void Simulator::pollForMAVLinkMessages(bool publish) pthread_create(&sender_thread, &sender_thread_attr, Simulator::sending_trampoline, NULL); pthread_attr_destroy(&sender_thread_attr); + mavlink_status_t udp_status = {}; + mavlink_status_t serial_status = {}; + // wait for new mavlink messages to arrive while (true) { @@ -555,10 +558,9 @@ void Simulator::pollForMAVLinkMessages(bool publish) if (len > 0) { mavlink_message_t msg; - mavlink_status_t status; for (int i = 0; i < len; i++) { - if (mavlink_parse_char(MAVLINK_COMM_0, _buf[i], &msg, &status)) { + if (mavlink_parse_char(MAVLINK_COMM_0, _buf[i], &msg, &udp_status)) { // have a message, handle it handle_message(&msg, publish); } @@ -572,10 +574,9 @@ void Simulator::pollForMAVLinkMessages(bool publish) if (len > 0) { mavlink_message_t msg; - mavlink_status_t status; for (int i = 0; i < len; ++i) { - if (mavlink_parse_char(MAVLINK_COMM_1, serial_buf[i], &msg, &status)) { + if (mavlink_parse_char(MAVLINK_COMM_1, serial_buf[i], &msg, &serial_status)) { // have a message, handle it handle_message(&msg, true); }