From 44dc66196ad85d7f11ecd7f8407cf71b1c41c1b9 Mon Sep 17 00:00:00 2001 From: dongfang Date: Sat, 18 May 2013 20:15:13 +0200 Subject: [PATCH] Undone the HUD_old renaming and fixed public slots in PrimaryFlightDisply that were not. --- src/ui/HUD.cc | 144 ++++++++++++++++++++-------------------- src/ui/HUD.h | 46 ++++++------- src/ui/PrimaryFlightDisplay.cpp | 6 ++ src/ui/PrimaryFlightDisplay.h | 8 ++- src/ui/QGCRGBDView.cc | 4 +- src/ui/QGCRGBDView.h | 2 +- 6 files changed, 110 insertions(+), 100 deletions(-) diff --git a/src/ui/HUD.cc b/src/ui/HUD.cc index fdb28cc..7a4b56c 100644 --- a/src/ui/HUD.cc +++ b/src/ui/HUD.cc @@ -23,7 +23,7 @@ This file is part of the QGROUNDCONTROL project /** * @file - * @brief Head Up Display (HUD_old) + * @brief Head Up Display (HUD) * * @author Lorenz Meier * @@ -52,14 +52,14 @@ This file is part of the QGROUNDCONTROL project #endif /** - * @warning The HUD_old widget will not start painting its content automatically - * to update the view, start the auto-update by calling HUD_old::start(). + * @warning The HUD widget will not start painting its content automatically + * to update the view, start the auto-update by calling HUD::start(). * * @param width * @param height * @param parent */ -HUD_old::HUD_old(int width, int height, QWidget* parent) +HUD::HUD(int width, int height, QWidget* parent) : QGLWidget(QGLFormat(QGL::SampleBuffers), parent), uas(NULL), yawInt(0.0f), @@ -151,7 +151,7 @@ HUD_old::HUD_old(int width, int height, QWidget* parent) // Refresh timer refreshTimer->setInterval(updateInterval); - connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD_old())); + connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD())); // Resize to correct size and fill with image resize(this->width(), this->height()); @@ -186,17 +186,17 @@ HUD_old::HUD_old(int width, int height, QWidget* parent) if (UASManager::instance()->getActiveUAS() != NULL) setActiveUAS(UASManager::instance()->getActiveUAS()); } -HUD_old::~HUD_old() +HUD::~HUD() { refreshTimer->stop(); } -QSize HUD_old::sizeHint() const +QSize HUD::sizeHint() const { return QSize(width(), (width()*3.0f)/4); } -void HUD_old::showEvent(QShowEvent* event) +void HUD::showEvent(QShowEvent* event) { // React only to internal (pre-display) // events @@ -205,7 +205,7 @@ void HUD_old::showEvent(QShowEvent* event) emit visibilityChanged(true); } -void HUD_old::hideEvent(QHideEvent* event) +void HUD::hideEvent(QHideEvent* event) { // React only to internal (pre-display) // events @@ -214,7 +214,7 @@ void HUD_old::hideEvent(QHideEvent* event) emit visibilityChanged(false); } -void HUD_old::contextMenuEvent (QContextMenuEvent* event) +void HUD::contextMenuEvent (QContextMenuEvent* event) { QMenu menu(this); // Update actions @@ -222,17 +222,17 @@ void HUD_old::contextMenuEvent (QContextMenuEvent* event) enableVideoAction->setChecked(videoEnabled); menu.addAction(enableHUDAction); - //menu.addAction(selectHUD_oldColorAction); + //menu.addAction(selectHUDColorAction); menu.addAction(enableVideoAction); menu.addAction(selectOfflineDirectoryAction); menu.addAction(selectSaveDirectoryAction); menu.exec(event->globalPos()); } -void HUD_old::createActions() +void HUD::createActions() { - enableHUDAction = new QAction(tr("Enable HUD_old"), this); - enableHUDAction->setStatusTip(tr("Show the HUD_old instruments in this window")); + enableHUDAction = new QAction(tr("Enable HUD"), this); + enableHUDAction->setStatusTip(tr("Show the HUD instruments in this window")); enableHUDAction->setCheckable(true); enableHUDAction->setChecked(HUDInstrumentsEnabled); connect(enableHUDAction, SIGNAL(triggered(bool)), this, SLOT(enableHUDInstruments(bool))); @@ -255,9 +255,9 @@ void HUD_old::createActions() /** * - * @param uas the UAS/MAV to monitor/display with the HUD_old + * @param uas the UAS/MAV to monitor/display with the HUD */ -void HUD_old::setActiveUAS(UASInterface* uas) +void HUD::setActiveUAS(UASInterface* uas) { if (this->uas != NULL) { // Disconnect any previously connected active MAV @@ -308,7 +308,7 @@ void HUD_old::setActiveUAS(UASInterface* uas) } } -//void HUD_old::updateAttitudeThrustSetPoint(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 msec) +//void HUD::updateAttitudeThrustSetPoint(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 msec) //{ //// updateValue(uas, "roll desired", rollDesired, msec); //// updateValue(uas, "pitch desired", pitchDesired, msec); @@ -316,7 +316,7 @@ void HUD_old::setActiveUAS(UASInterface* uas) //// updateValue(uas, "thrust desired", thrustDesired, msec); //} -void HUD_old::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp) +void HUD::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp) { Q_UNUSED(uas); Q_UNUSED(timestamp); @@ -328,7 +328,7 @@ void HUD_old::updateAttitude(UASInterface* uas, double roll, double pitch, doubl } } -void HUD_old::updateAttitude(UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp) +void HUD::updateAttitude(UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp) { Q_UNUSED(uas); Q_UNUSED(timestamp); @@ -338,7 +338,7 @@ void HUD_old::updateAttitude(UASInterface* uas, int component, double roll, doub } } -void HUD_old::updateBattery(UASInterface* uas, double voltage, double percent, int seconds) +void HUD::updateBattery(UASInterface* uas, double voltage, double percent, int seconds) { Q_UNUSED(uas); Q_UNUSED(seconds); @@ -352,18 +352,18 @@ void HUD_old::updateBattery(UASInterface* uas, double voltage, double percent, i } } -void HUD_old::receiveHeartbeat(UASInterface*) +void HUD::receiveHeartbeat(UASInterface*) { } -void HUD_old::updateThrust(UASInterface* uas, double thrust) +void HUD::updateThrust(UASInterface* uas, double thrust) { Q_UNUSED(uas); Q_UNUSED(thrust); // updateValue(uas, "thrust", thrust, MG::TIME::getGroundTimeNow()); } -void HUD_old::updateLocalPosition(UASInterface* uas,double x,double y,double z,quint64 timestamp) +void HUD::updateLocalPosition(UASInterface* uas,double x,double y,double z,quint64 timestamp) { Q_UNUSED(uas); Q_UNUSED(timestamp); @@ -372,7 +372,7 @@ void HUD_old::updateLocalPosition(UASInterface* uas,double x,double y,double z,q this->zPos = z; } -void HUD_old::updateGlobalPosition(UASInterface* uas,double lat, double lon, double altitude, quint64 timestamp) +void HUD::updateGlobalPosition(UASInterface* uas,double lat, double lon, double altitude, quint64 timestamp) { Q_UNUSED(uas); Q_UNUSED(timestamp); @@ -381,7 +381,7 @@ void HUD_old::updateGlobalPosition(UASInterface* uas,double lat, double lon, dou this->alt = altitude; } -void HUD_old::updateSpeed(UASInterface* uas,double x,double y,double z,quint64 timestamp) +void HUD::updateSpeed(UASInterface* uas,double x,double y,double z,quint64 timestamp) { Q_UNUSED(uas); Q_UNUSED(timestamp); @@ -397,9 +397,9 @@ void HUD_old::updateSpeed(UASInterface* uas,double x,double y,double z,quint64 t * Updates the current system state, but only if the uas matches the currently monitored uas. * * @param uas the system the state message originates from - * @param state short state text, displayed in HUD_old + * @param state short state text, displayed in HUD */ -void HUD_old::updateState(UASInterface* uas,QString state) +void HUD::updateState(UASInterface* uas,QString state) { // Only one UAS is connected at a time Q_UNUSED(uas); @@ -410,9 +410,9 @@ void HUD_old::updateState(UASInterface* uas,QString state) * Updates the current system mode, but only if the uas matches the currently monitored uas. * * @param uas the system the state message originates from - * @param mode short mode text, displayed in HUD_old + * @param mode short mode text, displayed in HUD */ -void HUD_old::updateMode(int id,QString mode, QString description) +void HUD::updateMode(int id,QString mode, QString description) { // Only one UAS is connected at a time Q_UNUSED(id); @@ -420,7 +420,7 @@ void HUD_old::updateMode(int id,QString mode, QString description) this->mode = mode; } -void HUD_old::updateLoad(UASInterface* uas, double load) +void HUD::updateLoad(UASInterface* uas, double load) { Q_UNUSED(uas); this->load = load; @@ -431,7 +431,7 @@ void HUD_old::updateLoad(UASInterface* uas, double load) * @param y coordinate in pixels to be converted to reference mm units * @return the screen coordinate relative to the QGLWindow origin */ -float HUD_old::refToScreenX(float x) +float HUD::refToScreenX(float x) { //qDebug() << "sX: " << (scalingFactor * x) << "Orig:" << x; return (scalingFactor * x); @@ -440,7 +440,7 @@ float HUD_old::refToScreenX(float x) * @param x coordinate in pixels to be converted to reference mm units * @return the screen coordinate relative to the QGLWindow origin */ -float HUD_old::refToScreenY(float y) +float HUD::refToScreenY(float y) { //qDebug() << "sY: " << (scalingFactor * y); return (scalingFactor * y); @@ -451,7 +451,7 @@ float HUD_old::refToScreenY(float y) * the x and y center offsets. * */ -void HUD_old::paintCenterBackground(float roll, float pitch, float yaw) +void HUD::paintCenterBackground(float roll, float pitch, float yaw) { Q_UNUSED(yaw); @@ -459,7 +459,7 @@ void HUD_old::paintCenterBackground(float roll, float pitch, float yaw) float referenceWidth = 70.0; float referenceHeight = 70.0; - // HUD_old is assumed to be 200 x 150 mm + // HUD is assumed to be 200 x 150 mm // so that positions can be hardcoded // but can of course be scaled. @@ -522,7 +522,7 @@ void HUD_old::paintCenterBackground(float roll, float pitch, float yaw) * @param refX position in reference units (mm of the real instrument). This is relative to the measurement unit position, NOT in pixels. * @param refY position in reference units (mm of the real instrument). This is relative to the measurement unit position, NOT in pixels. */ -void HUD_old::paintText(QString text, QColor color, float fontSize, float refX, float refY, QPainter* painter) +void HUD::paintText(QString text, QColor color, float fontSize, float refX, float refY, QPainter* painter) { QPen prevPen = painter->pen(); float pPositionX = refToScreenX(refX) - (fontSize*scalingFactor*0.072f); @@ -546,7 +546,7 @@ void HUD_old::paintText(QString text, QColor color, float fontSize, float refX, painter->setPen(prevPen); } -void HUD_old::initializeGL() +void HUD::initializeGL() { bool antialiasing = true; @@ -575,7 +575,7 @@ void HUD_old::initializeGL() * @param referenceWidth width in the reference mm-unit space * @param referenceHeight width in the reference mm-unit space */ -void HUD_old::setupGLView(float referencePositionX, float referencePositionY, float referenceWidth, float referenceHeight) +void HUD::setupGLView(float referencePositionX, float referencePositionY, float referenceWidth, float referenceHeight) { int pixelWidth = (int)(referenceWidth * scalingFactor); int pixelHeight = (int)(referenceHeight * scalingFactor); @@ -601,12 +601,12 @@ void HUD_old::setupGLView(float referencePositionX, float referencePositionY, fl //glScalef(scaleX, scaleY, 1.0f); } -void HUD_old::paintRollPitchStrips() +void HUD::paintRollPitchStrips() { } -void HUD_old::paintEvent(QPaintEvent *event) +void HUD::paintEvent(QPaintEvent *event) { // Event is not needed // the event is ignored as this widget @@ -614,7 +614,7 @@ void HUD_old::paintEvent(QPaintEvent *event) Q_UNUSED(event); } -void HUD_old::paintHUD_old() +void HUD::paintHUD() { if (isVisible()) { // static quint64 interval = 0; @@ -900,7 +900,7 @@ void HUD_old::paintHUD_old() /** * @param pitch pitch angle in degrees (-180 to 180) */ -void HUD_old::paintPitchLines(float pitch, QPainter* painter) +void HUD::paintPitchLines(float pitch, QPainter* painter) { QString label; @@ -967,7 +967,7 @@ void HUD_old::paintPitchLines(float pitch, QPainter* painter) } } -void HUD_old::paintPitchLinePos(QString text, float refPosX, float refPosY, QPainter* painter) +void HUD::paintPitchLinePos(QString text, float refPosX, float refPosY, QPainter* painter) { //painter->setPen(QPen(QBrush, normalStrokeWidth)); @@ -996,7 +996,7 @@ void HUD_old::paintPitchLinePos(QString text, float refPosX, float refPosY, QPai drawLine(refPosX+pitchWidth/2.0f, refPosY, refPosX+pitchGap/2.0f, refPosY, lineWidth, defaultColor, painter); } -void HUD_old::paintPitchLineNeg(QString text, float refPosX, float refPosY, QPainter* painter) +void HUD::paintPitchLineNeg(QString text, float refPosX, float refPosY, QPainter* painter) { const float pitchWidth = 30.0f; const float pitchGap = pitchWidth / 2.5f; @@ -1046,7 +1046,7 @@ void rotatePointClockWise(QPointF& p, float angle) p.setY((-1.0f * sin(angle) * p.x()) + cos(angle) * p.y()); } -float HUD_old::refLineWidthToPen(float line) +float HUD::refLineWidthToPen(float line) { return line * 2.50f; } @@ -1059,7 +1059,7 @@ float HUD_old::refLineWidthToPen(float line) * @param angle rotation angle, in radians * @return p Polygon p rotated by angle around the origin point */ -void HUD_old::rotatePolygonClockWiseRad(QPolygonF& p, float angle, QPointF origin) +void HUD::rotatePolygonClockWiseRad(QPolygonF& p, float angle, QPointF origin) { // Standard 2x2 rotation matrix, counter-clockwise // @@ -1078,7 +1078,7 @@ void HUD_old::rotatePolygonClockWiseRad(QPolygonF& p, float angle, QPointF origi } } -void HUD_old::drawPolygon(QPolygonF refPolygon, QPainter* painter) +void HUD::drawPolygon(QPolygonF refPolygon, QPainter* painter) { // Scale coordinates QPolygonF draw(refPolygon.size()); @@ -1091,7 +1091,7 @@ void HUD_old::drawPolygon(QPolygonF refPolygon, QPainter* painter) painter->drawPolygon(draw); } -void HUD_old::drawChangeRateStrip(float xRef, float yRef, float height, float minRate, float maxRate, float value, QPainter* painter,bool reverse) +void HUD::drawChangeRateStrip(float xRef, float yRef, float height, float minRate, float maxRate, float value, QPainter* painter,bool reverse) { float scaledValue = value; @@ -1154,7 +1154,7 @@ void HUD_old::drawChangeRateStrip(float xRef, float yRef, float height, float mi } } -//void HUD_old::drawSystemIndicator(float xRef, float yRef, int maxNum, float maxWidth, float maxHeight, QPainter* painter) +//void HUD::drawSystemIndicator(float xRef, float yRef, int maxNum, float maxWidth, float maxHeight, QPainter* painter) //{ // Q_UNUSED(maxWidth); // Q_UNUSED(maxHeight); @@ -1231,7 +1231,7 @@ void HUD_old::drawChangeRateStrip(float xRef, float yRef, float height, float mi // } //} -void HUD_old::drawChangeIndicatorGauge(float xRef, float yRef, float radius, float expectedMaxChange, float value, const QColor& color, QPainter* painter, bool solid) +void HUD::drawChangeIndicatorGauge(float xRef, float yRef, float radius, float expectedMaxChange, float value, const QColor& color, QPainter* painter, bool solid) { // Draw the circle QPen circlePen(Qt::SolidLine); @@ -1277,7 +1277,7 @@ void HUD_old::drawChangeIndicatorGauge(float xRef, float yRef, float radius, flo drawPolygon(p, painter); } -void HUD_old::drawLine(float refX1, float refY1, float refX2, float refY2, float width, const QColor& color, QPainter* painter) +void HUD::drawLine(float refX1, float refY1, float refX2, float refY2, float width, const QColor& color, QPainter* painter) { QPen pen(Qt::SolidLine); pen.setWidth(refLineWidthToPen(width)); @@ -1286,7 +1286,7 @@ void HUD_old::drawLine(float refX1, float refY1, float refX2, float refY2, float painter->drawLine(QPoint(refToScreenX(refX1), refToScreenY(refY1)), QPoint(refToScreenX(refX2), refToScreenY(refY2))); } -void HUD_old::drawEllipse(float refX, float refY, float radiusX, float radiusY, float startDeg, float endDeg, float lineWidth, const QColor& color, QPainter* painter) +void HUD::drawEllipse(float refX, float refY, float radiusX, float radiusY, float startDeg, float endDeg, float lineWidth, const QColor& color, QPainter* painter) { Q_UNUSED(startDeg); Q_UNUSED(endDeg); @@ -1297,12 +1297,12 @@ void HUD_old::drawEllipse(float refX, float refY, float radiusX, float radiusY, painter->drawEllipse(QPointF(refToScreenX(refX), refToScreenY(refY)), refToScreenX(radiusX), refToScreenY(radiusY)); } -void HUD_old::drawCircle(float refX, float refY, float radius, float startDeg, float endDeg, float lineWidth, const QColor& color, QPainter* painter) +void HUD::drawCircle(float refX, float refY, float radius, float startDeg, float endDeg, float lineWidth, const QColor& color, QPainter* painter) { drawEllipse(refX, refY, radius, radius, startDeg, endDeg, lineWidth, color, painter); } -void HUD_old::resizeGL(int w, int h) +void HUD::resizeGL(int w, int h) { if (isVisible()) { glViewport(0, 0, w, h); @@ -1312,17 +1312,17 @@ void HUD_old::resizeGL(int w, int h) glMatrixMode(GL_MODELVIEW); glPolygonMode(GL_FRONT, GL_FILL); //FIXME - paintHUD_old(); + paintHUD(); } } -void HUD_old::selectWaypoint(int uasId, int id) +void HUD::selectWaypoint(int uasId, int id) { Q_UNUSED(uasId); waypointName = tr("WP") + QString::number(id); } -void HUD_old::setImageSize(int width, int height, int depth, int channels) +void HUD::setImageSize(int width, int height, int depth, int channels) { // Allocate raw image in correct size if (width != receivedWidth || height != receivedHeight || depth != receivedDepth || channels != receivedChannels || image == NULL) { @@ -1378,10 +1378,10 @@ void HUD_old::setImageSize(int width, int height, int depth, int channels) } -void HUD_old::startImage(int imgid, int width, int height, int depth, int channels) +void HUD::startImage(int imgid, int width, int height, int depth, int channels) { Q_UNUSED(imgid); - //qDebug() << "HUD_old: starting image (" << width << "x" << height << ", " << depth << "bits) with " << channels << "channels"; + //qDebug() << "HUD: starting image (" << width << "x" << height << ", " << depth << "bits) with " << channels << "channels"; // Copy previous image to screen if it hasn't been finished properly finishImage(); @@ -1391,7 +1391,7 @@ void HUD_old::startImage(int imgid, int width, int height, int depth, int channe imageStarted = true; } -void HUD_old::finishImage() +void HUD::finishImage() { if (imageStarted) { commitRawDataToGL(); @@ -1399,7 +1399,7 @@ void HUD_old::finishImage() } } -void HUD_old::commitRawDataToGL() +void HUD::commitRawDataToGL() { qDebug() << __FILE__ << __LINE__ << "Copying raw data to GL buffer:" << rawImage << receivedWidth << receivedHeight << image->format(); if (image != NULL) { @@ -1429,19 +1429,19 @@ void HUD_old::commitRawDataToGL() update(); } -void HUD_old::saveImage(QString fileName) +void HUD::saveImage(QString fileName) { image->save(fileName); } -void HUD_old::saveImage() +void HUD::saveImage() { //Bring up popup QString fileName = "output.png"; saveImage(fileName); } -void HUD_old::startImage(quint64 timestamp) +void HUD::startImage(quint64 timestamp) { if (videoEnabled && offlineDirectory != "") { // Load and diplay image file @@ -1449,7 +1449,7 @@ void HUD_old::startImage(quint64 timestamp) } } -void HUD_old::selectOfflineDirectory() +void HUD::selectOfflineDirectory() { QString fileName = QFileDialog::getExistingDirectory(this, tr("Select image directory"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation)); if (fileName != "") { @@ -1457,17 +1457,17 @@ void HUD_old::selectOfflineDirectory() } } -void HUD_old::enableHUD_oldInstruments(bool enabled) +void HUD::enableHUDInstruments(bool enabled) { HUDInstrumentsEnabled = enabled; } -void HUD_old::enableVideo(bool enabled) +void HUD::enableVideo(bool enabled) { videoEnabled = enabled; } -void HUD_old::setPixels(int imgid, const unsigned char* imageData, int length, int startIndex) +void HUD::setPixels(int imgid, const unsigned char* imageData, int length, int startIndex) { Q_UNUSED(imgid); // qDebug() << "at" << __FILE__ << __LINE__ << ": Received startindex" << startIndex << "and length" << length << "(" << startIndex+length << "of" << rawExpectedBytes << "bytes)"; @@ -1478,7 +1478,7 @@ void HUD_old::setPixels(int imgid, const unsigned char* imageData, int length, i if (startIndex+length > rawExpectedBytes) { - qDebug() << "HUD_old: OVERFLOW! startIndex:" << startIndex << "length:" << length << "image raw size" << ((receivedWidth * receivedHeight * receivedChannels * receivedDepth) / 8) - 1; + qDebug() << "HUD: OVERFLOW! startIndex:" << startIndex << "length:" << length << "image raw size" << ((receivedWidth * receivedHeight * receivedChannels * receivedDepth) / 8) - 1; } else { @@ -1489,7 +1489,7 @@ void HUD_old::setPixels(int imgid, const unsigned char* imageData, int length, i // Check if we just reached the end of the image if (startIndex+length == rawExpectedBytes) { - //qDebug() << "HUD_old: END OF IMAGE REACHED!"; + //qDebug() << "HUD: END OF IMAGE REACHED!"; finishImage(); rawLastIndex = 0; } @@ -1507,11 +1507,11 @@ void HUD_old::setPixels(int imgid, const unsigned char* imageData, int length, i } } -void HUD_old::copyImage() +void HUD::copyImage() { if (isVisible() && HUDInstrumentsEnabled) { - //qDebug() << "HUD_old::copyImage()"; + //qDebug() << "HUD::copyImage()"; UAS* u = dynamic_cast(this->uas); if (u) { @@ -1527,7 +1527,7 @@ void HUD_old::copyImage() } } -void HUD_old::saveImages(bool save) +void HUD::saveImages(bool save) { if (save) { diff --git a/src/ui/HUD.h b/src/ui/HUD.h index d1c2130..720b1f0 100644 --- a/src/ui/HUD.h +++ b/src/ui/HUD.h @@ -29,8 +29,8 @@ This file is part of the QGROUNDCONTROL project * */ -#ifndef HUD_old_H -#define HUD_old_H +#ifndef HUD_H +#define HUD_H #include #include @@ -41,18 +41,18 @@ This file is part of the QGROUNDCONTROL project #include "UASInterface.h" /** - * @brief Displays a Head Up Display (HUD_old) + * @brief Displays a Head Up Display (HUD) * - * This class represents a head up display (HUD_old) and draws this HUD_old in an OpenGL widget (QGLWidget). - * It can superimpose the HUD_old over the current live image stream (any arriving image stream will be auto- + * This class represents a head up display (HUD) and draws this HUD in an OpenGL widget (QGLWidget). + * It can superimpose the HUD over the current live image stream (any arriving image stream will be auto- * matically used as background), or it draws the classic blue-brown background known from instruments. */ -class HUD_old : public QGLWidget +class HUD : public QGLWidget { Q_OBJECT public: - HUD_old(int width = 640, int height = 480, QWidget* parent = NULL); - ~HUD_old(); + HUD(int width = 640, int height = 480, QWidget* parent = NULL); + ~HUD(); void setImageSize(int width, int height, int depth, int channels); void resizeGL(int w, int h); @@ -90,7 +90,7 @@ public slots: /** @brief Select directory where to load the offline files from */ void selectOfflineDirectory(); /** @brief Enable the HUD instruments */ - void enableHUD_oldInstruments(bool enabled); + void enableHUDInstruments(bool enabled); /** @brief Enable Video */ void enableVideo(bool enabled); /** @brief Copy an image from the current active UAS */ @@ -103,9 +103,9 @@ protected slots: void paintPitchLines(float pitch, QPainter* painter); /** @brief Paint text on top of the image and OpenGL drawings */ void paintText(QString text, QColor color, float fontSize, float refX, float refY, QPainter* painter); - /** @brief Setup the OpenGL view for drawing a sub-component of the HUD_old */ + /** @brief Setup the OpenGL view for drawing a sub-component of the HUD */ void setupGLView(float referencePositionX, float referencePositionY, float referenceWidth, float referenceHeight); - void paintHUD_old(); + void paintHUD(); void paintPitchLinePos(QString text, float refPosX, float refPosY, QPainter* painter); void paintPitchLineNeg(QString text, float refPosX, float refPosY, QPainter* painter); @@ -156,8 +156,8 @@ protected: float vGaugeSpacing; ///< Virtual spacing of the gauges from the center, 50 mm per default float vPitchPerDeg; ///< Virtual pitch to mm conversion. Currently one degree is 3 mm up/down in the pitch markings - int xCenter; ///< Center of the HUD_old instrument in pixel coordinates. Allows to off-center the whole instrument in its OpenGL window, e.g. to fit another instrument - int yCenter; ///< Center of the HUD_old instrument in pixel coordinates. Allows to off-center the whole instrument in its OpenGL window, e.g. to fit another instrument + int xCenter; ///< Center of the HUD instrument in pixel coordinates. Allows to off-center the whole instrument in its OpenGL window, e.g. to fit another instrument + int yCenter; ///< Center of the HUD instrument in pixel coordinates. Allows to off-center the whole instrument in its OpenGL window, e.g. to fit another instrument // Image buffers unsigned char* rawBuffer1; ///< Double buffer 1 for the image @@ -172,8 +172,8 @@ protected: int receivedWidth; ///< Width in pixels of the current image int receivedHeight; ///< Height in pixels of the current image - // HUD_old colors - QColor defaultColor; ///< Color for most HUD_old elements, e.g. pitch lines, center cross, change rate gauges + // HUD colors + QColor defaultColor; ///< Color for most HUD elements, e.g. pitch lines, center cross, change rate gauges QColor setPointColor; ///< Color for the current control set point, e.g. yaw desired QColor warningColor; ///< Color for warning messages QColor criticalColor; ///< Color for caution messages @@ -184,17 +184,17 @@ protected: int warningBlinkRate; ///< Blink rate of warning messages, will be rounded to the refresh rate QTimer* refreshTimer; ///< The main timer, controls the update rate - QPainter* HUD_oldPainter; - QFont font; ///< The HUD_old font, per default the free Bitstream Vera SANS, which is very close to actual HUD_old fonts - QFontDatabase fontDatabase;///< Font database, only used to load the TrueType font file (the HUD_old font is directly loaded from file rather than from the system) + QPainter* HUDPainter; + 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) bool noCamera; ///< No camera images available, draw the ground/sky box to indicate the horizon bool hardwareAcceleration; ///< Enable hardware acceleration - float strongStrokeWidth; ///< Strong line stroke width, used throughout the HUD_old - float normalStrokeWidth; ///< Normal line stroke width, used throughout the HUD_old - float fineStrokeWidth; ///< Fine line stroke width, used throughout the HUD_old + float strongStrokeWidth; ///< Strong line stroke width, used throughout the HUD + float normalStrokeWidth; ///< Normal line stroke width, used throughout the HUD + float fineStrokeWidth; ///< Fine line stroke width, used throughout the HUD - QString waypointName; ///< Waypoint name displayed in HUD_old + QString waypointName; ///< Waypoint name displayed in HUD float roll; float pitch; float yaw; @@ -235,4 +235,4 @@ protected: unsigned int imageLogCounter; }; -#endif // HUD_old_H +#endif // HUD_H diff --git a/src/ui/PrimaryFlightDisplay.cpp b/src/ui/PrimaryFlightDisplay.cpp index 0990174..e317895 100644 --- a/src/ui/PrimaryFlightDisplay.cpp +++ b/src/ui/PrimaryFlightDisplay.cpp @@ -170,6 +170,8 @@ void PrimaryFlightDisplay::updateAttitude(UASInterface* uas, double roll, double this->heading = yaw; } // TODO: Else-part. We really should have an "attitude bad or unknown" indication instead of just freezing. + + qDebug("r,p,y: %f,%f,%f", roll, pitch, yaw); } /* @@ -184,6 +186,8 @@ void PrimaryFlightDisplay::updateAttitude(UASInterface* uas, int component, doub Q_UNUSED(pitch); Q_UNUSED(yaw); Q_UNUSED(timestamp); + + qDebug("ignore (!!!) r,p,y: %f,%f,%f", roll, pitch, yaw); } void PrimaryFlightDisplay::updateBattery(UASInterface* uas, double voltage, double percent, int seconds) @@ -1122,3 +1126,5 @@ void PrimaryFlightDisplay::doPaint() { paintAllInOne(); #endif } + +void PrimaryFlightDisplay:: createActions() {} diff --git a/src/ui/PrimaryFlightDisplay.h b/src/ui/PrimaryFlightDisplay.h index 33cb8b1..cbfad8f 100644 --- a/src/ui/PrimaryFlightDisplay.h +++ b/src/ui/PrimaryFlightDisplay.h @@ -84,6 +84,7 @@ public: PrimaryFlightDisplay(int width = 640, int height = 480, QWidget* parent = NULL); ~PrimaryFlightDisplay(); +public slots: /** @brief Attitude from main autopilot / system state */ void updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp); /** @brief Attitude from one specific component / redundant autopilot */ @@ -100,6 +101,7 @@ public: void updateLoad(UASInterface*, double); void selectWaypoint(int uasId, int id); +protected: void paintEvent(QPaintEvent *event); void resizeEvent(QResizeEvent *e); @@ -115,11 +117,10 @@ public: // dongfang: We have no context menu. Viewonly. // void contextMenuEvent (QContextMenuEvent* event); +protected: // dongfang: What is that? void createActions(); - static const int updateInterval = 40; - public slots: /** @brief Set the currently monitored UAS */ virtual void setActiveUAS(UASInterface* uas); @@ -208,6 +209,9 @@ private: static const int tickValues[]; static const QString compassWindNames[]; + static const int updateInterval = 40; + + signals: public slots: diff --git a/src/ui/QGCRGBDView.cc b/src/ui/QGCRGBDView.cc index 72d8c3a..27f3e34 100644 --- a/src/ui/QGCRGBDView.cc +++ b/src/ui/QGCRGBDView.cc @@ -6,7 +6,7 @@ #include "UASManager.h" QGCRGBDView::QGCRGBDView(int width, int height, QWidget *parent) : - HUD_old(width, height, parent), + HUD(width, height, parent), rgbEnabled(false), depthEnabled(false) { @@ -70,7 +70,7 @@ void QGCRGBDView::setActiveUAS(UASInterface* uas) connect(uas, SIGNAL(rgbdImageChanged(UASInterface*)), this, SLOT(updateData(UASInterface*))); } - HUD_old::setActiveUAS(uas); + HUD::setActiveUAS(uas); } void QGCRGBDView::clearData(void) diff --git a/src/ui/QGCRGBDView.h b/src/ui/QGCRGBDView.h index 9689566..58b1503 100644 --- a/src/ui/QGCRGBDView.h +++ b/src/ui/QGCRGBDView.h @@ -3,7 +3,7 @@ #include "HUD.h" -class QGCRGBDView : public HUD_old +class QGCRGBDView : public HUD { Q_OBJECT public: