diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index dff9c3c4bb41da9de0adcf17a290873e380b1cbf..db86ad8efa93ac84db12e2aed5a71176bafebd21 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -68,6 +68,8 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox) memset(totalLossCounter, 0, sizeof(totalLossCounter)); memset(runningLossPercent, 0, sizeof(runningLossPercent)); memset(firstMessage, 1, sizeof(firstMessage)); + memset(&_status, 0, sizeof(_status)); + memset(&_message, 0, sizeof(_message)); } MAVLinkProtocol::~MAVLinkProtocol() diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h index 35947162b6902dbec6508a71772047fc1ba5e9db..cd2a30568511b0aaa31ded882cdc7c0224e549b3 100644 --- a/src/comm/MAVLinkProtocol.h +++ b/src/comm/MAVLinkProtocol.h @@ -108,8 +108,8 @@ protected: uint64_t totalLossCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< Total messages lost during transmission. float runningLossPercent[MAVLINK_COMM_NUM_BUFFERS]; ///< Loss rate - mavlink_message_t _message = {}; - mavlink_status_t _status = {}; + mavlink_message_t _message; + mavlink_status_t _status; bool versionMismatchIgnore; int systemId;