diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 020516b52afb28eb404c2e00a965eb122e21e9db..8201184a047461124bac447d66b3ee7d05606a57 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1329,10 +1329,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ++imagePacketsArrived; // emit signal if all packets arrived + // && seq >= imagePackets-1 if ((imagePacketsArrived >= imagePackets)) { // Restart statemachine emit imageReady(this); + //imagePacketsArrived = 0; + //imagePackets = 0; //qDebug() << "imageReady emitted. all packets arrived"; } } @@ -2142,11 +2145,16 @@ QImage UAS::getImage() if (!image.loadFromData(imageRecBuffer)) { qDebug() << __FILE__ << __LINE__ << "Loading data from image buffer failed!"; + //imagePacketsArrived = 0; + //imagePackets = 0; + return QImage(); } } + // Restart statemachine imagePacketsArrived = 0; - //imageRecBuffer.clear(); + imagePackets = 0; + imageRecBuffer.clear(); return image; } @@ -3148,7 +3156,7 @@ void UAS::sendHilGroundTruth(quint64 time_us, float roll, float pitch, float yaw Q_UNUSED(xacc); Q_UNUSED(yacc); Q_UNUSED(zacc); - + // Emit attitude for cross-check emit valueChanged(uasId, "roll sim", "rad", roll, getUnixTime()); emit valueChanged(uasId, "pitch sim", "rad", pitch, getUnixTime()); diff --git a/src/ui/HUD.cc b/src/ui/HUD.cc index 90b1ca0b7f3b4044b782545722930c8ac8151db5..e4386ae8edfb57d90224a8c72be50482a56862d0 100644 --- a/src/ui/HUD.cc +++ b/src/ui/HUD.cc @@ -119,7 +119,7 @@ HUD::HUD(int width, int height, QWidget* parent) { Q_UNUSED(width); Q_UNUSED(height); - + // Set auto fill to false setAutoFillBackground(false); @@ -1374,7 +1374,10 @@ void HUD::copyImage(UASInterface* uas) UAS* u = qobject_cast(uas); if (u) { - this->glImage = u->getImage(); + QImage temp_im = u->getImage(); + if (temp_im.byteCount() > 0) { + this->glImage = temp_im;//u->getImage(); + } // Save to directory if logging is enabled if (imageLoggingEnabled)