Commit 178bc32c authored by LM's avatar LM

Fixed image transmission code

parent 919c2b20
This diff is collapsed.
...@@ -187,7 +187,8 @@ protected: //COMMENTS FOR TEST UNIT ...@@ -187,7 +187,8 @@ protected: //COMMENTS FOR TEST UNIT
int imagePackets; ///< Number of data packets being sent for this image int imagePackets; ///< Number of data packets being sent for this image
int imagePacketsArrived; ///< Number of data packets recieved int imagePacketsArrived; ///< Number of data packets recieved
int imagePayload; ///< Payload size per transmitted packet (bytes). Standard is 254, and decreases when image resolution increases. int imagePayload; ///< Payload size per transmitted packet (bytes). Standard is 254, and decreases when image resolution increases.
int imageQuality; ///< JPEG-Quality of the transmitted image (percentage) int imageQuality; ///< Quality of the transmitted image (percentage)
int imageType; ///< Type of the transmitted image (BMP, PNG, JPEG, RAW 8 bit, RAW 32 bit)
QByteArray imageRecBuffer; ///< Buffer for the incoming bytestream QByteArray imageRecBuffer; ///< Buffer for the incoming bytestream
QImage image; ///< Image data of last completely transmitted image QImage image; ///< Image data of last completely transmitted image
quint64 imageStart; quint64 imageStart;
......
...@@ -106,7 +106,6 @@ HUD::HUD(int width, int height, QWidget* parent) ...@@ -106,7 +106,6 @@ HUD::HUD(int width, int height, QWidget* parent)
fuelColor(criticalColor), fuelColor(criticalColor),
warningBlinkRate(5), warningBlinkRate(5),
refreshTimer(new QTimer(this)), refreshTimer(new QTimer(this)),
imageTimer(new QTimer(this)),
noCamera(true), noCamera(true),
hardwareAcceleration(true), hardwareAcceleration(true),
strongStrokeWidth(1.5f), strongStrokeWidth(1.5f),
...@@ -161,14 +160,11 @@ HUD::HUD(int width, int height, QWidget* parent) ...@@ -161,14 +160,11 @@ HUD::HUD(int width, int height, QWidget* parent)
//qDebug() << __FILE__ << __LINE__ << "template image:" << imagePath; //qDebug() << __FILE__ << __LINE__ << "template image:" << imagePath;
//fill = QImage(imagePath); //fill = QImage(imagePath);
//glImage = QGLWidget::convertToGLFormat(fill); glImage = QGLWidget::convertToGLFormat(fill);
// Refresh timer // Refresh timer
refreshTimer->setInterval(updateInterval); refreshTimer->setInterval(updateInterval);
imageTimer->setInterval(250);
//connect(refreshTimer, SIGNAL(timeout()), this, SLOT(update()));
connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD())); connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD()));
// connect(imageTimer, SIGNAL(timeout()), this, SLOT(requestNewImage())); TODO
// Resize to correct size and fill with image // Resize to correct size and fill with image
//glDrawPixels(glImage.width(), glImage.height(), GL_RGBA, GL_UNSIGNED_BYTE, glImage.bits()); //glDrawPixels(glImage.width(), glImage.height(), GL_RGBA, GL_UNSIGNED_BYTE, glImage.bits());
...@@ -207,7 +203,6 @@ HUD::HUD(int width, int height, QWidget* parent) ...@@ -207,7 +203,6 @@ HUD::HUD(int width, int height, QWidget* parent)
HUD::~HUD() HUD::~HUD()
{ {
refreshTimer->stop(); refreshTimer->stop();
imageTimer->stop();
} }
QSize HUD::sizeHint() const QSize HUD::sizeHint() const
...@@ -288,7 +283,7 @@ void HUD::setActiveUAS(UASInterface* uas) ...@@ -288,7 +283,7 @@ void HUD::setActiveUAS(UASInterface* uas)
UAS* u = dynamic_cast<UAS*>(this->uas); UAS* u = dynamic_cast<UAS*>(this->uas);
if (u) { if (u) {
disconnect(u, SIGNAL(imageStarted(quint64)), this, SLOT(startImage(quint64))); disconnect(u, SIGNAL(imageStarted(quint64)), this, SLOT(startImage(quint64)));
disconnect(u, SIGNAL(imageReady(UASInterface*)), this, SLOT(requestNewImage())); disconnect(u, SIGNAL(imageReady(UASInterface*)), this, SLOT(copyImage()));
} }
} }
...@@ -310,7 +305,7 @@ void HUD::setActiveUAS(UASInterface* uas) ...@@ -310,7 +305,7 @@ void HUD::setActiveUAS(UASInterface* uas)
UAS* u = dynamic_cast<UAS*>(uas); UAS* u = dynamic_cast<UAS*>(uas);
if (u) { if (u) {
connect(u, SIGNAL(imageStarted(quint64)), this, SLOT(startImage(quint64))); connect(u, SIGNAL(imageStarted(quint64)), this, SLOT(startImage(quint64)));
connect(u, SIGNAL(imageReady(UASInterface*)), this, SLOT(requestNewImage())); connect(u, SIGNAL(imageReady(UASInterface*)), this, SLOT(copyImage()));
} }
// Set new UAS // Set new UAS
...@@ -675,9 +670,6 @@ void HUD::paintHUD() ...@@ -675,9 +670,6 @@ void HUD::paintHUD()
qDebug() << __FILE__ << __LINE__ << "template image:" << nextOfflineImage; qDebug() << __FILE__ << __LINE__ << "template image:" << nextOfflineImage;
QImage fill = QImage(nextOfflineImage); QImage fill = QImage(nextOfflineImage);
xImageFactor = width() / (float)fill.width();
yImageFactor = height() / (float)fill.height();
glImage = QGLWidget::convertToGLFormat(fill); glImage = QGLWidget::convertToGLFormat(fill);
// Reset to save load efforts // Reset to save load efforts
...@@ -686,9 +678,13 @@ void HUD::paintHUD() ...@@ -686,9 +678,13 @@ void HUD::paintHUD()
glRasterPos2i(0, 0); glRasterPos2i(0, 0);
glPixelZoom(xImageFactor, yImageFactor); xImageFactor = width() / (float)glImage.width();
yImageFactor = height() / (float)glImage.height();
float imageFactor = qMin(xImageFactor, yImageFactor);
glPixelZoom(imageFactor, imageFactor);
// Resize to correct size and fill with image // Resize to correct size and fill with image
glDrawPixels(glImage.width(), glImage.height(), GL_RGBA, GL_UNSIGNED_BYTE, glImage.bits()); glDrawPixels(glImage.width(), glImage.height(), GL_RGBA, GL_UNSIGNED_BYTE, glImage.bits());
//qDebug() << "DRAWING GL IMAGE";
} else { } else {
// Blue / brown background // Blue / brown background
paintCenterBackground(roll, pitch, yawTrans); paintCenterBackground(roll, pitch, yawTrans);
...@@ -1633,17 +1629,8 @@ void HUD::setPixels(int imgid, const unsigned char* imageData, int length, int s ...@@ -1633,17 +1629,8 @@ void HUD::setPixels(int imgid, const unsigned char* imageData, int length, int s
} }
} }
void HUD::requestNewImage() void HUD::copyImage()
{ {
qDebug() << "HUD::requestNewImage()"; qDebug() << "HUD::copyImage()";
// if (!imageRequested) this->glImage = QGLWidget::convertToGLFormat(this->u->getImage());
// {
// this->u->requestImage();
// imageRequested = true;
// }
// else
// {
this->glImage = this->u->getImage();
// imageRequested = false;
// }
} }
...@@ -88,8 +88,8 @@ public slots: ...@@ -88,8 +88,8 @@ public slots:
void enableHUDInstruments(bool enabled); void enableHUDInstruments(bool enabled);
/** @brief Enable Video */ /** @brief Enable Video */
void enableVideo(bool enabled); void enableVideo(bool enabled);
/** @brief Handler for image transmission */ /** @brief Copy an image from the current active UAS */
void requestNewImage(); void copyImage();
protected slots: protected slots:
...@@ -176,7 +176,6 @@ protected: ...@@ -176,7 +176,6 @@ protected:
int warningBlinkRate; ///< Blink rate of warning messages, will be rounded to the refresh rate int warningBlinkRate; ///< Blink rate of warning messages, will be rounded to the refresh rate
QTimer* refreshTimer; ///< The main timer, controls the update rate QTimer* refreshTimer; ///< The main timer, controls the update rate
QTimer* imageTimer; ///< The timer for the image update rate
QPainter* hudPainter; QPainter* hudPainter;
QFont font; ///< The HUD font, per default the free Bitstream Vera SANS, which is very close to actual HUD fonts QFont font; ///< The HUD font, per default the free Bitstream Vera SANS, which is very close to actual HUD fonts
QFontDatabase fontDatabase;///< Font database, only used to load the TrueType font file (the HUD font is directly loaded from file rather than from the system) QFontDatabase fontDatabase;///< Font database, only used to load the TrueType font file (the HUD font is directly loaded from file rather than from the system)
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment