Browse Source

First PrimaryFlightDisplay integration that will even compile. Non functionalgit status

QGC4.4
dongfang 12 years ago
parent
commit
84ed67cd65
  1. 6
      qgroundcontrol.pro
  2. 156
      src/ui/HUD.cc
  3. 48
      src/ui/HUD.h
  4. 15
      src/ui/MainWindow.cc
  5. 1124
      src/ui/PrimaryFlightDisplay.cpp
  6. 217
      src/ui/PrimaryFlightDisplay.h
  7. 6
      src/ui/QGCRGBDView.cc
  8. 2
      src/ui/QGCRGBDView.h

6
qgroundcontrol.pro

@ -376,7 +376,8 @@ HEADERS += src/MG.h \
src/ui/submainwindow.h \ src/ui/submainwindow.h \
src/ui/dockwidgettitlebareventfilter.h \ src/ui/dockwidgettitlebareventfilter.h \
src/ui/uas/UASQuickView.h \ src/ui/uas/UASQuickView.h \
src/ui/uas/UASQuickViewItem.h src/ui/uas/UASQuickViewItem.h \
src/ui/PrimaryFlightDisplay.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler # Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
@ -544,7 +545,8 @@ SOURCES += src/main.cc \
src/ui/submainwindow.cpp \ src/ui/submainwindow.cpp \
src/ui/dockwidgettitlebareventfilter.cpp \ src/ui/dockwidgettitlebareventfilter.cpp \
src/ui/uas/UASQuickViewItem.cc \ src/ui/uas/UASQuickViewItem.cc \
src/ui/uas/UASQuickView.cc src/ui/uas/UASQuickView.cc \
src/ui/PrimaryFlightDisplay.cpp
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler # Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc

156
src/ui/HUD.cc

@ -23,7 +23,7 @@ This file is part of the QGROUNDCONTROL project
/** /**
* @file * @file
* @brief Head Up Display (HUD) * @brief Head Up Display (HUD_old)
* *
* @author Lorenz Meier <mavteam@student.ethz.ch> * @author Lorenz Meier <mavteam@student.ethz.ch>
* *
@ -52,14 +52,14 @@ This file is part of the QGROUNDCONTROL project
#endif #endif
/** /**
* @warning The HUD widget will not start painting its content automatically * @warning The HUD_old widget will not start painting its content automatically
* to update the view, start the auto-update by calling HUD::start(). * to update the view, start the auto-update by calling HUD_old::start().
* *
* @param width * @param width
* @param height * @param height
* @param parent * @param parent
*/ */
HUD::HUD(int width, int height, QWidget* parent) HUD_old::HUD_old(int width, int height, QWidget* parent)
: QGLWidget(QGLFormat(QGL::SampleBuffers), parent), : QGLWidget(QGLFormat(QGL::SampleBuffers), parent),
uas(NULL), uas(NULL),
yawInt(0.0f), yawInt(0.0f),
@ -119,7 +119,7 @@ HUD::HUD(int width, int height, QWidget* parent)
load(0.0f), load(0.0f),
offlineDirectory(""), offlineDirectory(""),
nextOfflineImage(""), nextOfflineImage(""),
hudInstrumentsEnabled(true), HUDInstrumentsEnabled(true),
videoEnabled(false), videoEnabled(false),
xImageFactor(1.0), xImageFactor(1.0),
yImageFactor(1.0), yImageFactor(1.0),
@ -151,7 +151,7 @@ HUD::HUD(int width, int height, QWidget* parent)
// Refresh timer // Refresh timer
refreshTimer->setInterval(updateInterval); refreshTimer->setInterval(updateInterval);
connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD())); connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD_old()));
// Resize to correct size and fill with image // Resize to correct size and fill with image
resize(this->width(), this->height()); resize(this->width(), this->height());
@ -186,17 +186,17 @@ HUD::HUD(int width, int height, QWidget* parent)
if (UASManager::instance()->getActiveUAS() != NULL) setActiveUAS(UASManager::instance()->getActiveUAS()); if (UASManager::instance()->getActiveUAS() != NULL) setActiveUAS(UASManager::instance()->getActiveUAS());
} }
HUD::~HUD() HUD_old::~HUD_old()
{ {
refreshTimer->stop(); refreshTimer->stop();
} }
QSize HUD::sizeHint() const QSize HUD_old::sizeHint() const
{ {
return QSize(width(), (width()*3.0f)/4); return QSize(width(), (width()*3.0f)/4);
} }
void HUD::showEvent(QShowEvent* event) void HUD_old::showEvent(QShowEvent* event)
{ {
// React only to internal (pre-display) // React only to internal (pre-display)
// events // events
@ -205,7 +205,7 @@ void HUD::showEvent(QShowEvent* event)
emit visibilityChanged(true); emit visibilityChanged(true);
} }
void HUD::hideEvent(QHideEvent* event) void HUD_old::hideEvent(QHideEvent* event)
{ {
// React only to internal (pre-display) // React only to internal (pre-display)
// events // events
@ -214,27 +214,27 @@ void HUD::hideEvent(QHideEvent* event)
emit visibilityChanged(false); emit visibilityChanged(false);
} }
void HUD::contextMenuEvent (QContextMenuEvent* event) void HUD_old::contextMenuEvent (QContextMenuEvent* event)
{ {
QMenu menu(this); QMenu menu(this);
// Update actions // Update actions
enableHUDAction->setChecked(hudInstrumentsEnabled); enableHUDAction->setChecked(HUDInstrumentsEnabled);
enableVideoAction->setChecked(videoEnabled); enableVideoAction->setChecked(videoEnabled);
menu.addAction(enableHUDAction); menu.addAction(enableHUDAction);
//menu.addAction(selectHUDColorAction); //menu.addAction(selectHUD_oldColorAction);
menu.addAction(enableVideoAction); menu.addAction(enableVideoAction);
menu.addAction(selectOfflineDirectoryAction); menu.addAction(selectOfflineDirectoryAction);
menu.addAction(selectSaveDirectoryAction); menu.addAction(selectSaveDirectoryAction);
menu.exec(event->globalPos()); menu.exec(event->globalPos());
} }
void HUD::createActions() void HUD_old::createActions()
{ {
enableHUDAction = new QAction(tr("Enable HUD"), this); enableHUDAction = new QAction(tr("Enable HUD_old"), this);
enableHUDAction->setStatusTip(tr("Show the HUD instruments in this window")); enableHUDAction->setStatusTip(tr("Show the HUD_old instruments in this window"));
enableHUDAction->setCheckable(true); enableHUDAction->setCheckable(true);
enableHUDAction->setChecked(hudInstrumentsEnabled); enableHUDAction->setChecked(HUDInstrumentsEnabled);
connect(enableHUDAction, SIGNAL(triggered(bool)), this, SLOT(enableHUDInstruments(bool))); connect(enableHUDAction, SIGNAL(triggered(bool)), this, SLOT(enableHUDInstruments(bool)));
enableVideoAction = new QAction(tr("Enable Video Live feed"), this); enableVideoAction = new QAction(tr("Enable Video Live feed"), this);
@ -255,9 +255,9 @@ void HUD::createActions()
/** /**
* *
* @param uas the UAS/MAV to monitor/display with the HUD * @param uas the UAS/MAV to monitor/display with the HUD_old
*/ */
void HUD::setActiveUAS(UASInterface* uas) void HUD_old::setActiveUAS(UASInterface* uas)
{ {
if (this->uas != NULL) { if (this->uas != NULL) {
// Disconnect any previously connected active MAV // Disconnect any previously connected active MAV
@ -308,7 +308,7 @@ void HUD::setActiveUAS(UASInterface* uas)
} }
} }
//void HUD::updateAttitudeThrustSetPoint(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 msec) //void HUD_old::updateAttitudeThrustSetPoint(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 msec)
//{ //{
//// updateValue(uas, "roll desired", rollDesired, msec); //// updateValue(uas, "roll desired", rollDesired, msec);
//// updateValue(uas, "pitch desired", pitchDesired, msec); //// updateValue(uas, "pitch desired", pitchDesired, msec);
@ -316,7 +316,7 @@ void HUD::setActiveUAS(UASInterface* uas)
//// updateValue(uas, "thrust desired", thrustDesired, msec); //// updateValue(uas, "thrust desired", thrustDesired, msec);
//} //}
void HUD::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp) void HUD_old::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp)
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
Q_UNUSED(timestamp); Q_UNUSED(timestamp);
@ -328,7 +328,7 @@ void HUD::updateAttitude(UASInterface* uas, double roll, double pitch, double ya
} }
} }
void HUD::updateAttitude(UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp) void HUD_old::updateAttitude(UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp)
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
Q_UNUSED(timestamp); Q_UNUSED(timestamp);
@ -338,7 +338,7 @@ void HUD::updateAttitude(UASInterface* uas, int component, double roll, double p
} }
} }
void HUD::updateBattery(UASInterface* uas, double voltage, double percent, int seconds) void HUD_old::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
Q_UNUSED(seconds); Q_UNUSED(seconds);
@ -352,18 +352,18 @@ void HUD::updateBattery(UASInterface* uas, double voltage, double percent, int s
} }
} }
void HUD::receiveHeartbeat(UASInterface*) void HUD_old::receiveHeartbeat(UASInterface*)
{ {
} }
void HUD::updateThrust(UASInterface* uas, double thrust) void HUD_old::updateThrust(UASInterface* uas, double thrust)
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
Q_UNUSED(thrust); Q_UNUSED(thrust);
// updateValue(uas, "thrust", thrust, MG::TIME::getGroundTimeNow()); // updateValue(uas, "thrust", thrust, MG::TIME::getGroundTimeNow());
} }
void HUD::updateLocalPosition(UASInterface* uas,double x,double y,double z,quint64 timestamp) void HUD_old::updateLocalPosition(UASInterface* uas,double x,double y,double z,quint64 timestamp)
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
Q_UNUSED(timestamp); Q_UNUSED(timestamp);
@ -372,7 +372,7 @@ void HUD::updateLocalPosition(UASInterface* uas,double x,double y,double z,quint
this->zPos = z; this->zPos = z;
} }
void HUD::updateGlobalPosition(UASInterface* uas,double lat, double lon, double altitude, quint64 timestamp) void HUD_old::updateGlobalPosition(UASInterface* uas,double lat, double lon, double altitude, quint64 timestamp)
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
Q_UNUSED(timestamp); Q_UNUSED(timestamp);
@ -381,7 +381,7 @@ void HUD::updateGlobalPosition(UASInterface* uas,double lat, double lon, double
this->alt = altitude; this->alt = altitude;
} }
void HUD::updateSpeed(UASInterface* uas,double x,double y,double z,quint64 timestamp) void HUD_old::updateSpeed(UASInterface* uas,double x,double y,double z,quint64 timestamp)
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
Q_UNUSED(timestamp); Q_UNUSED(timestamp);
@ -397,9 +397,9 @@ void HUD::updateSpeed(UASInterface* uas,double x,double y,double z,quint64 times
* Updates the current system state, but only if the uas matches the currently monitored uas. * 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 uas the system the state message originates from
* @param state short state text, displayed in HUD * @param state short state text, displayed in HUD_old
*/ */
void HUD::updateState(UASInterface* uas,QString state) void HUD_old::updateState(UASInterface* uas,QString state)
{ {
// Only one UAS is connected at a time // Only one UAS is connected at a time
Q_UNUSED(uas); Q_UNUSED(uas);
@ -410,9 +410,9 @@ void HUD::updateState(UASInterface* uas,QString state)
* Updates the current system mode, but only if the uas matches the currently monitored uas. * 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 uas the system the state message originates from
* @param mode short mode text, displayed in HUD * @param mode short mode text, displayed in HUD_old
*/ */
void HUD::updateMode(int id,QString mode, QString description) void HUD_old::updateMode(int id,QString mode, QString description)
{ {
// Only one UAS is connected at a time // Only one UAS is connected at a time
Q_UNUSED(id); Q_UNUSED(id);
@ -420,7 +420,7 @@ void HUD::updateMode(int id,QString mode, QString description)
this->mode = mode; this->mode = mode;
} }
void HUD::updateLoad(UASInterface* uas, double load) void HUD_old::updateLoad(UASInterface* uas, double load)
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
this->load = load; this->load = load;
@ -431,7 +431,7 @@ void HUD::updateLoad(UASInterface* uas, double load)
* @param y coordinate in pixels to be converted to reference mm units * @param y coordinate in pixels to be converted to reference mm units
* @return the screen coordinate relative to the QGLWindow origin * @return the screen coordinate relative to the QGLWindow origin
*/ */
float HUD::refToScreenX(float x) float HUD_old::refToScreenX(float x)
{ {
//qDebug() << "sX: " << (scalingFactor * x) << "Orig:" << x; //qDebug() << "sX: " << (scalingFactor * x) << "Orig:" << x;
return (scalingFactor * x); return (scalingFactor * x);
@ -440,7 +440,7 @@ float HUD::refToScreenX(float x)
* @param x coordinate in pixels to be converted to reference mm units * @param x coordinate in pixels to be converted to reference mm units
* @return the screen coordinate relative to the QGLWindow origin * @return the screen coordinate relative to the QGLWindow origin
*/ */
float HUD::refToScreenY(float y) float HUD_old::refToScreenY(float y)
{ {
//qDebug() << "sY: " << (scalingFactor * y); //qDebug() << "sY: " << (scalingFactor * y);
return (scalingFactor * y); return (scalingFactor * y);
@ -451,7 +451,7 @@ float HUD::refToScreenY(float y)
* the x and y center offsets. * the x and y center offsets.
* *
*/ */
void HUD::paintCenterBackground(float roll, float pitch, float yaw) void HUD_old::paintCenterBackground(float roll, float pitch, float yaw)
{ {
Q_UNUSED(yaw); Q_UNUSED(yaw);
@ -459,7 +459,7 @@ void HUD::paintCenterBackground(float roll, float pitch, float yaw)
float referenceWidth = 70.0; float referenceWidth = 70.0;
float referenceHeight = 70.0; float referenceHeight = 70.0;
// HUD is assumed to be 200 x 150 mm // HUD_old is assumed to be 200 x 150 mm
// so that positions can be hardcoded // so that positions can be hardcoded
// but can of course be scaled. // but can of course be scaled.
@ -522,7 +522,7 @@ void HUD::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 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. * @param refY position in reference units (mm of the real instrument). This is relative to the measurement unit position, NOT in pixels.
*/ */
void HUD::paintText(QString text, QColor color, float fontSize, float refX, float refY, QPainter* painter) void HUD_old::paintText(QString text, QColor color, float fontSize, float refX, float refY, QPainter* painter)
{ {
QPen prevPen = painter->pen(); QPen prevPen = painter->pen();
float pPositionX = refToScreenX(refX) - (fontSize*scalingFactor*0.072f); float pPositionX = refToScreenX(refX) - (fontSize*scalingFactor*0.072f);
@ -546,7 +546,7 @@ void HUD::paintText(QString text, QColor color, float fontSize, float refX, floa
painter->setPen(prevPen); painter->setPen(prevPen);
} }
void HUD::initializeGL() void HUD_old::initializeGL()
{ {
bool antialiasing = true; bool antialiasing = true;
@ -575,7 +575,7 @@ void HUD::initializeGL()
* @param referenceWidth width in the reference mm-unit space * @param referenceWidth width in the reference mm-unit space
* @param referenceHeight width in the reference mm-unit space * @param referenceHeight width in the reference mm-unit space
*/ */
void HUD::setupGLView(float referencePositionX, float referencePositionY, float referenceWidth, float referenceHeight) void HUD_old::setupGLView(float referencePositionX, float referencePositionY, float referenceWidth, float referenceHeight)
{ {
int pixelWidth = (int)(referenceWidth * scalingFactor); int pixelWidth = (int)(referenceWidth * scalingFactor);
int pixelHeight = (int)(referenceHeight * scalingFactor); int pixelHeight = (int)(referenceHeight * scalingFactor);
@ -601,12 +601,12 @@ void HUD::setupGLView(float referencePositionX, float referencePositionY, float
//glScalef(scaleX, scaleY, 1.0f); //glScalef(scaleX, scaleY, 1.0f);
} }
void HUD::paintRollPitchStrips() void HUD_old::paintRollPitchStrips()
{ {
} }
void HUD::paintEvent(QPaintEvent *event) void HUD_old::paintEvent(QPaintEvent *event)
{ {
// Event is not needed // Event is not needed
// the event is ignored as this widget // the event is ignored as this widget
@ -614,7 +614,7 @@ void HUD::paintEvent(QPaintEvent *event)
Q_UNUSED(event); Q_UNUSED(event);
} }
void HUD::paintHUD() void HUD_old::paintHUD_old()
{ {
if (isVisible()) { if (isVisible()) {
// static quint64 interval = 0; // static quint64 interval = 0;
@ -711,7 +711,7 @@ void HUD::paintHUD()
// END OF OPENGL PAINTING // END OF OPENGL PAINTING
if (hudInstrumentsEnabled) { if (HUDInstrumentsEnabled) {
//glEnable(GL_MULTISAMPLE); //glEnable(GL_MULTISAMPLE);
@ -900,7 +900,7 @@ void HUD::paintHUD()
/** /**
* @param pitch pitch angle in degrees (-180 to 180) * @param pitch pitch angle in degrees (-180 to 180)
*/ */
void HUD::paintPitchLines(float pitch, QPainter* painter) void HUD_old::paintPitchLines(float pitch, QPainter* painter)
{ {
QString label; QString label;
@ -967,7 +967,7 @@ void HUD::paintPitchLines(float pitch, QPainter* painter)
} }
} }
void HUD::paintPitchLinePos(QString text, float refPosX, float refPosY, QPainter* painter) void HUD_old::paintPitchLinePos(QString text, float refPosX, float refPosY, QPainter* painter)
{ {
//painter->setPen(QPen(QBrush, normalStrokeWidth)); //painter->setPen(QPen(QBrush, normalStrokeWidth));
@ -996,7 +996,7 @@ void HUD::paintPitchLinePos(QString text, float refPosX, float refPosY, QPainter
drawLine(refPosX+pitchWidth/2.0f, refPosY, refPosX+pitchGap/2.0f, refPosY, lineWidth, defaultColor, painter); drawLine(refPosX+pitchWidth/2.0f, refPosY, refPosX+pitchGap/2.0f, refPosY, lineWidth, defaultColor, painter);
} }
void HUD::paintPitchLineNeg(QString text, float refPosX, float refPosY, QPainter* painter) void HUD_old::paintPitchLineNeg(QString text, float refPosX, float refPosY, QPainter* painter)
{ {
const float pitchWidth = 30.0f; const float pitchWidth = 30.0f;
const float pitchGap = pitchWidth / 2.5f; 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()); p.setY((-1.0f * sin(angle) * p.x()) + cos(angle) * p.y());
} }
float HUD::refLineWidthToPen(float line) float HUD_old::refLineWidthToPen(float line)
{ {
return line * 2.50f; return line * 2.50f;
} }
@ -1059,7 +1059,7 @@ float HUD::refLineWidthToPen(float line)
* @param angle rotation angle, in radians * @param angle rotation angle, in radians
* @return p Polygon p rotated by angle around the origin point * @return p Polygon p rotated by angle around the origin point
*/ */
void HUD::rotatePolygonClockWiseRad(QPolygonF& p, float angle, QPointF origin) void HUD_old::rotatePolygonClockWiseRad(QPolygonF& p, float angle, QPointF origin)
{ {
// Standard 2x2 rotation matrix, counter-clockwise // Standard 2x2 rotation matrix, counter-clockwise
// //
@ -1078,7 +1078,7 @@ void HUD::rotatePolygonClockWiseRad(QPolygonF& p, float angle, QPointF origin)
} }
} }
void HUD::drawPolygon(QPolygonF refPolygon, QPainter* painter) void HUD_old::drawPolygon(QPolygonF refPolygon, QPainter* painter)
{ {
// Scale coordinates // Scale coordinates
QPolygonF draw(refPolygon.size()); QPolygonF draw(refPolygon.size());
@ -1091,7 +1091,7 @@ void HUD::drawPolygon(QPolygonF refPolygon, QPainter* painter)
painter->drawPolygon(draw); painter->drawPolygon(draw);
} }
void HUD::drawChangeRateStrip(float xRef, float yRef, float height, float minRate, float maxRate, float value, QPainter* painter,bool reverse) void HUD_old::drawChangeRateStrip(float xRef, float yRef, float height, float minRate, float maxRate, float value, QPainter* painter,bool reverse)
{ {
float scaledValue = value; float scaledValue = value;
@ -1154,7 +1154,7 @@ void HUD::drawChangeRateStrip(float xRef, float yRef, float height, float minRat
} }
} }
//void HUD::drawSystemIndicator(float xRef, float yRef, int maxNum, float maxWidth, float maxHeight, QPainter* painter) //void HUD_old::drawSystemIndicator(float xRef, float yRef, int maxNum, float maxWidth, float maxHeight, QPainter* painter)
//{ //{
// Q_UNUSED(maxWidth); // Q_UNUSED(maxWidth);
// Q_UNUSED(maxHeight); // Q_UNUSED(maxHeight);
@ -1231,7 +1231,7 @@ void HUD::drawChangeRateStrip(float xRef, float yRef, float height, float minRat
// } // }
//} //}
void HUD::drawChangeIndicatorGauge(float xRef, float yRef, float radius, float expectedMaxChange, float value, const QColor& color, QPainter* painter, bool solid) void HUD_old::drawChangeIndicatorGauge(float xRef, float yRef, float radius, float expectedMaxChange, float value, const QColor& color, QPainter* painter, bool solid)
{ {
// Draw the circle // Draw the circle
QPen circlePen(Qt::SolidLine); QPen circlePen(Qt::SolidLine);
@ -1277,7 +1277,7 @@ void HUD::drawChangeIndicatorGauge(float xRef, float yRef, float radius, float e
drawPolygon(p, painter); drawPolygon(p, painter);
} }
void HUD::drawLine(float refX1, float refY1, float refX2, float refY2, float width, const QColor& color, QPainter* painter) void HUD_old::drawLine(float refX1, float refY1, float refX2, float refY2, float width, const QColor& color, QPainter* painter)
{ {
QPen pen(Qt::SolidLine); QPen pen(Qt::SolidLine);
pen.setWidth(refLineWidthToPen(width)); pen.setWidth(refLineWidthToPen(width));
@ -1286,7 +1286,7 @@ void HUD::drawLine(float refX1, float refY1, float refX2, float refY2, float wid
painter->drawLine(QPoint(refToScreenX(refX1), refToScreenY(refY1)), QPoint(refToScreenX(refX2), refToScreenY(refY2))); painter->drawLine(QPoint(refToScreenX(refX1), refToScreenY(refY1)), QPoint(refToScreenX(refX2), refToScreenY(refY2)));
} }
void HUD::drawEllipse(float refX, float refY, float radiusX, float radiusY, float startDeg, float endDeg, float lineWidth, const QColor& color, QPainter* painter) void HUD_old::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(startDeg);
Q_UNUSED(endDeg); Q_UNUSED(endDeg);
@ -1297,12 +1297,12 @@ void HUD::drawEllipse(float refX, float refY, float radiusX, float radiusY, floa
painter->drawEllipse(QPointF(refToScreenX(refX), refToScreenY(refY)), refToScreenX(radiusX), refToScreenY(radiusY)); painter->drawEllipse(QPointF(refToScreenX(refX), refToScreenY(refY)), refToScreenX(radiusX), refToScreenY(radiusY));
} }
void HUD::drawCircle(float refX, float refY, float radius, float startDeg, float endDeg, float lineWidth, const QColor& color, QPainter* painter) void HUD_old::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); drawEllipse(refX, refY, radius, radius, startDeg, endDeg, lineWidth, color, painter);
} }
void HUD::resizeGL(int w, int h) void HUD_old::resizeGL(int w, int h)
{ {
if (isVisible()) { if (isVisible()) {
glViewport(0, 0, w, h); glViewport(0, 0, w, h);
@ -1312,17 +1312,17 @@ void HUD::resizeGL(int w, int h)
glMatrixMode(GL_MODELVIEW); glMatrixMode(GL_MODELVIEW);
glPolygonMode(GL_FRONT, GL_FILL); glPolygonMode(GL_FRONT, GL_FILL);
//FIXME //FIXME
paintHUD(); paintHUD_old();
} }
} }
void HUD::selectWaypoint(int uasId, int id) void HUD_old::selectWaypoint(int uasId, int id)
{ {
Q_UNUSED(uasId); Q_UNUSED(uasId);
waypointName = tr("WP") + QString::number(id); waypointName = tr("WP") + QString::number(id);
} }
void HUD::setImageSize(int width, int height, int depth, int channels) void HUD_old::setImageSize(int width, int height, int depth, int channels)
{ {
// Allocate raw image in correct size // Allocate raw image in correct size
if (width != receivedWidth || height != receivedHeight || depth != receivedDepth || channels != receivedChannels || image == NULL) { if (width != receivedWidth || height != receivedHeight || depth != receivedDepth || channels != receivedChannels || image == NULL) {
@ -1378,10 +1378,10 @@ void HUD::setImageSize(int width, int height, int depth, int channels)
} }
void HUD::startImage(int imgid, int width, int height, int depth, int channels) void HUD_old::startImage(int imgid, int width, int height, int depth, int channels)
{ {
Q_UNUSED(imgid); Q_UNUSED(imgid);
//qDebug() << "HUD: starting image (" << width << "x" << height << ", " << depth << "bits) with " << channels << "channels"; //qDebug() << "HUD_old: starting image (" << width << "x" << height << ", " << depth << "bits) with " << channels << "channels";
// Copy previous image to screen if it hasn't been finished properly // Copy previous image to screen if it hasn't been finished properly
finishImage(); finishImage();
@ -1391,7 +1391,7 @@ void HUD::startImage(int imgid, int width, int height, int depth, int channels)
imageStarted = true; imageStarted = true;
} }
void HUD::finishImage() void HUD_old::finishImage()
{ {
if (imageStarted) { if (imageStarted) {
commitRawDataToGL(); commitRawDataToGL();
@ -1399,7 +1399,7 @@ void HUD::finishImage()
} }
} }
void HUD::commitRawDataToGL() void HUD_old::commitRawDataToGL()
{ {
qDebug() << __FILE__ << __LINE__ << "Copying raw data to GL buffer:" << rawImage << receivedWidth << receivedHeight << image->format(); qDebug() << __FILE__ << __LINE__ << "Copying raw data to GL buffer:" << rawImage << receivedWidth << receivedHeight << image->format();
if (image != NULL) { if (image != NULL) {
@ -1429,19 +1429,19 @@ void HUD::commitRawDataToGL()
update(); update();
} }
void HUD::saveImage(QString fileName) void HUD_old::saveImage(QString fileName)
{ {
image->save(fileName); image->save(fileName);
} }
void HUD::saveImage() void HUD_old::saveImage()
{ {
//Bring up popup //Bring up popup
QString fileName = "output.png"; QString fileName = "output.png";
saveImage(fileName); saveImage(fileName);
} }
void HUD::startImage(quint64 timestamp) void HUD_old::startImage(quint64 timestamp)
{ {
if (videoEnabled && offlineDirectory != "") { if (videoEnabled && offlineDirectory != "") {
// Load and diplay image file // Load and diplay image file
@ -1449,7 +1449,7 @@ void HUD::startImage(quint64 timestamp)
} }
} }
void HUD::selectOfflineDirectory() void HUD_old::selectOfflineDirectory()
{ {
QString fileName = QFileDialog::getExistingDirectory(this, tr("Select image directory"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation)); QString fileName = QFileDialog::getExistingDirectory(this, tr("Select image directory"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation));
if (fileName != "") { if (fileName != "") {
@ -1457,17 +1457,17 @@ void HUD::selectOfflineDirectory()
} }
} }
void HUD::enableHUDInstruments(bool enabled) void HUD_old::enableHUD_oldInstruments(bool enabled)
{ {
hudInstrumentsEnabled = enabled; HUDInstrumentsEnabled = enabled;
} }
void HUD::enableVideo(bool enabled) void HUD_old::enableVideo(bool enabled)
{ {
videoEnabled = enabled; videoEnabled = enabled;
} }
void HUD::setPixels(int imgid, const unsigned char* imageData, int length, int startIndex) void HUD_old::setPixels(int imgid, const unsigned char* imageData, int length, int startIndex)
{ {
Q_UNUSED(imgid); Q_UNUSED(imgid);
// qDebug() << "at" << __FILE__ << __LINE__ << ": Received startindex" << startIndex << "and length" << length << "(" << startIndex+length << "of" << rawExpectedBytes << "bytes)"; // qDebug() << "at" << __FILE__ << __LINE__ << ": Received startindex" << startIndex << "and length" << length << "(" << startIndex+length << "of" << rawExpectedBytes << "bytes)";
@ -1478,7 +1478,7 @@ void HUD::setPixels(int imgid, const unsigned char* imageData, int length, int s
if (startIndex+length > rawExpectedBytes) if (startIndex+length > rawExpectedBytes)
{ {
qDebug() << "HUD: OVERFLOW! startIndex:" << startIndex << "length:" << length << "image raw size" << ((receivedWidth * receivedHeight * receivedChannels * receivedDepth) / 8) - 1; qDebug() << "HUD_old: OVERFLOW! startIndex:" << startIndex << "length:" << length << "image raw size" << ((receivedWidth * receivedHeight * receivedChannels * receivedDepth) / 8) - 1;
} }
else else
{ {
@ -1489,7 +1489,7 @@ void HUD::setPixels(int imgid, const unsigned char* imageData, int length, int s
// Check if we just reached the end of the image // Check if we just reached the end of the image
if (startIndex+length == rawExpectedBytes) if (startIndex+length == rawExpectedBytes)
{ {
//qDebug() << "HUD: END OF IMAGE REACHED!"; //qDebug() << "HUD_old: END OF IMAGE REACHED!";
finishImage(); finishImage();
rawLastIndex = 0; rawLastIndex = 0;
} }
@ -1507,11 +1507,11 @@ void HUD::setPixels(int imgid, const unsigned char* imageData, int length, int s
} }
} }
void HUD::copyImage() void HUD_old::copyImage()
{ {
if (isVisible() && hudInstrumentsEnabled) if (isVisible() && HUDInstrumentsEnabled)
{ {
//qDebug() << "HUD::copyImage()"; //qDebug() << "HUD_old::copyImage()";
UAS* u = dynamic_cast<UAS*>(this->uas); UAS* u = dynamic_cast<UAS*>(this->uas);
if (u) if (u)
{ {
@ -1527,7 +1527,7 @@ void HUD::copyImage()
} }
} }
void HUD::saveImages(bool save) void HUD_old::saveImages(bool save)
{ {
if (save) if (save)
{ {

48
src/ui/HUD.h

@ -29,8 +29,8 @@ This file is part of the QGROUNDCONTROL project
* *
*/ */
#ifndef HUD_H #ifndef HUD_old_H
#define HUD_H #define HUD_old_H
#include <QImage> #include <QImage>
#include <QGLWidget> #include <QGLWidget>
@ -41,18 +41,18 @@ This file is part of the QGROUNDCONTROL project
#include "UASInterface.h" #include "UASInterface.h"
/** /**
* @brief Displays a Head Up Display (HUD) * @brief Displays a Head Up Display (HUD_old)
* *
* This class represents a head up display (HUD) and draws this HUD in an OpenGL widget (QGLWidget). * This class represents a head up display (HUD_old) and draws this HUD_old in an OpenGL widget (QGLWidget).
* It can superimpose the HUD over the current live image stream (any arriving image stream will be auto- * It can superimpose the HUD_old 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. * matically used as background), or it draws the classic blue-brown background known from instruments.
*/ */
class HUD : public QGLWidget class HUD_old : public QGLWidget
{ {
Q_OBJECT Q_OBJECT
public: public:
HUD(int width = 640, int height = 480, QWidget* parent = NULL); HUD_old(int width = 640, int height = 480, QWidget* parent = NULL);
~HUD(); ~HUD_old();
void setImageSize(int width, int height, int depth, int channels); void setImageSize(int width, int height, int depth, int channels);
void resizeGL(int w, int h); void resizeGL(int w, int h);
@ -90,7 +90,7 @@ public slots:
/** @brief Select directory where to load the offline files from */ /** @brief Select directory where to load the offline files from */
void selectOfflineDirectory(); void selectOfflineDirectory();
/** @brief Enable the HUD instruments */ /** @brief Enable the HUD instruments */
void enableHUDInstruments(bool enabled); void enableHUD_oldInstruments(bool enabled);
/** @brief Enable Video */ /** @brief Enable Video */
void enableVideo(bool enabled); void enableVideo(bool enabled);
/** @brief Copy an image from the current active UAS */ /** @brief Copy an image from the current active UAS */
@ -103,9 +103,9 @@ protected slots:
void paintPitchLines(float pitch, QPainter* painter); void paintPitchLines(float pitch, QPainter* painter);
/** @brief Paint text on top of the image and OpenGL drawings */ /** @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); 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 */ /** @brief Setup the OpenGL view for drawing a sub-component of the HUD_old */
void setupGLView(float referencePositionX, float referencePositionY, float referenceWidth, float referenceHeight); void setupGLView(float referencePositionX, float referencePositionY, float referenceWidth, float referenceHeight);
void paintHUD(); void paintHUD_old();
void paintPitchLinePos(QString text, float refPosX, float refPosY, QPainter* painter); void paintPitchLinePos(QString text, float refPosX, float refPosY, QPainter* painter);
void paintPitchLineNeg(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 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 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 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_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 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
// Image buffers // Image buffers
unsigned char* rawBuffer1; ///< Double buffer 1 for the image unsigned char* rawBuffer1; ///< Double buffer 1 for the image
@ -172,8 +172,8 @@ protected:
int receivedWidth; ///< Width in pixels of the current image int receivedWidth; ///< Width in pixels of the current image
int receivedHeight; ///< Height in pixels of the current image int receivedHeight; ///< Height in pixels of the current image
// HUD colors // HUD_old colors
QColor defaultColor; ///< Color for most HUD elements, e.g. pitch lines, center cross, change rate gauges QColor defaultColor; ///< Color for most HUD_old elements, e.g. pitch lines, center cross, change rate gauges
QColor setPointColor; ///< Color for the current control set point, e.g. yaw desired QColor setPointColor; ///< Color for the current control set point, e.g. yaw desired
QColor warningColor; ///< Color for warning messages QColor warningColor; ///< Color for warning messages
QColor criticalColor; ///< Color for caution 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 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
QPainter* hudPainter; QPainter* HUD_oldPainter;
QFont font; ///< The HUD font, per default the free Bitstream Vera SANS, which is very close to actual HUD fonts 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 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_old 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 noCamera; ///< No camera images available, draw the ground/sky box to indicate the horizon
bool hardwareAcceleration; ///< Enable hardware acceleration bool hardwareAcceleration; ///< Enable hardware acceleration
float strongStrokeWidth; ///< Strong line stroke width, used throughout the HUD float strongStrokeWidth; ///< Strong line stroke width, used throughout the HUD_old
float normalStrokeWidth; ///< Normal line stroke width, used throughout the HUD float normalStrokeWidth; ///< Normal line stroke width, used throughout the HUD_old
float fineStrokeWidth; ///< Fine line stroke width, used throughout the HUD float fineStrokeWidth; ///< Fine line stroke width, used throughout the HUD_old
QString waypointName; ///< Waypoint name displayed in HUD QString waypointName; ///< Waypoint name displayed in HUD_old
float roll; float roll;
float pitch; float pitch;
float yaw; float yaw;
@ -218,7 +218,7 @@ protected:
float load; float load;
QString offlineDirectory; QString offlineDirectory;
QString nextOfflineImage; QString nextOfflineImage;
bool hudInstrumentsEnabled; bool HUDInstrumentsEnabled;
bool videoEnabled; bool videoEnabled;
bool dataStreamEnabled; bool dataStreamEnabled;
bool imageLoggingEnabled; bool imageLoggingEnabled;
@ -235,4 +235,4 @@ protected:
unsigned int imageLogCounter; unsigned int imageLogCounter;
}; };
#endif // HUD_H #endif // HUD_old_H

15
src/ui/MainWindow.cc

@ -59,6 +59,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGCFirmwareUpdate.h" #include "QGCFirmwareUpdate.h"
#include "QGCStatusBar.h" #include "QGCStatusBar.h"
#include "UASQuickView.h" #include "UASQuickView.h"
#include "PrimaryFlightDisplay.h"
#ifdef QGC_OSG_ENABLED #ifdef QGC_OSG_ENABLED
#include "Q3DWidgetFactory.h" #include "Q3DWidgetFactory.h"
@ -566,11 +567,14 @@ void MainWindow::buildCommonWidgets()
connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool))); connect(tempAction,SIGNAL(triggered(bool)),this, SLOT(showTool(bool)));
} }
// createDockWidget(simView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea,this->width()/1.5);
createDockWidget(simView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea,this->width()/1.5); createDockWidget(simView,new PrimaryFlightDisplay(320,240,this),tr("Primary Flight Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",VIEW_SIMULATION,Qt::RightDockWidgetArea,this->width()/1.5);
createDockWidget(pilotView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea); createDockWidget(pilotView,new UASListWidget(this),tr("Unmanned Systems"),"UNMANNED_SYSTEM_LIST_DOCKWIDGET",VIEW_FLIGHT,Qt::RightDockWidgetArea);
createDockWidget(pilotView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8);
//createDockWidget(pilotView,new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8);
createDockWidget(pilotView,new PrimaryFlightDisplay(320,240,this),tr("Primary Flight Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea,this->width()/1.8);
createDockWidget(pilotView,new UASQuickView(this),tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); createDockWidget(pilotView,new UASQuickView(this),tr("Quick View"),"UAS_INFO_QUICKVIEW_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
createDockWidget(pilotView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea); createDockWidget(pilotView,new HSIDisplay(this),tr("Horizontal Situation"),"HORIZONTAL_SITUATION_INDICATOR_DOCKWIDGET",VIEW_FLIGHT,Qt::LeftDockWidgetArea);
pilotView->setTabPosition(Qt::LeftDockWidgetArea,QTabWidget::North); pilotView->setTabPosition(Qt::LeftDockWidgetArea,QTabWidget::North);
@ -780,9 +784,10 @@ void MainWindow::loadDockWidget(QString name)
qDebug() << "Error loading window:" << name << "Unknown window type"; qDebug() << "Error loading window:" << name << "Unknown window type";
//createDockWidget(centerStack->currentWidget(),hddisplay,tr("Actuator Status"),"HEADS_DOWN_DISPLAY_2_DOCKWIDGET",currentView,Qt::RightDockWidgetArea); //createDockWidget(centerStack->currentWidget(),hddisplay,tr("Actuator Status"),"HEADS_DOWN_DISPLAY_2_DOCKWIDGET",currentView,Qt::RightDockWidgetArea);
} }
else if (name == "HEAD_UP_DISPLAY_DOCKWIDGET") else if (name == "PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET")
{ {
createDockWidget(centerStack->currentWidget(),new HUD(320,240,this),tr("Head Up Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea); // createDockWidget(centerStack->currentWidget(),new HUD(320,240,this),tr("Head Up Display"),"PRIMARY_FLIGHT_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea);
createDockWidget(centerStack->currentWidget(),new PrimaryFlightDisplay(320,240,this),tr("Primary Flight Display"),"HEAD_UP_DISPLAY_DOCKWIDGET",currentView,Qt::RightDockWidgetArea);
} }
else if (name == "UAS_INFO_QUICKVIEW_DOCKWIDGET") else if (name == "UAS_INFO_QUICKVIEW_DOCKWIDGET")
{ {

1124
src/ui/PrimaryFlightDisplay.cpp

File diff suppressed because it is too large Load Diff

217
src/ui/PrimaryFlightDisplay.h

@ -0,0 +1,217 @@
#ifndef PRIMARYFLIGHTDISPLAY_H
#define PRIMARYFLIGHTDISPLAY_H
#include <QWidget>
#include <QPen>
#include "UASInterface.h"
#define SEPARATE_LAYOUT
#define LINEWIDTH 0.007
// all in units of display height
#define ROLL_SCALE_RADIUS 0.42
#define ROLL_SCALE_TICKMARKLENGTH 0.04
#define ROLL_SCALE_MARKERWIDTH 0.06
#define ROLL_SCALE_MARKERHEIGHT 0.04
// scale max. degrees
#define ROLL_SCALE_RANGE 60
// fraction of height to translate for each degree of pitch.
#define PITCHTRANSLATION 65.0
// 10 degrees for each line
#define PITCH_SCALE_RESOLUTION 5
#define PITCH_SCALE_MAJORLENGTH 0.08
#define PITCH_SCALE_MINORLENGTH 0.04
#define PITCH_SCALE_HALFRANGE 20
//#define USE_TAPE_COMPASS
//#define USE_DISK_COMPASS
#define USE_DISK2_COMPASS
// We want no numbers on the scale, just principal winds or half-winds and ticks.
// With whole winds there are 45 deg per wind, with half-winds 22.5
#define COMPASS_TAPE_RESOLUTION 15
// number of degrees side to side
#define COMPASS_TAPE_SPAN 120
// The number of degrees to either side of the heading to draw the compass disk.
// 180 is valid, this will draw a complete disk. If the disk is partly clipped
// away, less will do.
#define COMPASS_DISK_SPAN 180
#define COMPASS_DISK_RESOLUTION 15
#define COMPASS_DISK_MARKERWIDTH 0.2
#define COMPASS_DISK_MARKERHEIGHT 0.133
#define COMPASS_DISK2_SPAN 180
#define COMPASS_DISK2_RESOLUTION 5
#define COMPASS_DISK2_MAJORTICK 10
#define COMPASS_DISK2_ARROWTICK 45
#define COMPASS_DISK2_MAJORLINEWIDTH 0.006
#define COMPASS_DISK2_MINORLINEWIDTH 0.004
#define COMPASS_SCALE_TEXT_SIZE 0.03
// The altitude difference between top and bottom of scale
#define ALTIMETER_LINEAR_SPAN 35
// every 5 meters there is a tick mark
#define ALTIMETER_LINEAR_RESOLUTION 5
// every 10 meters there is a number
#define ALTIMETER_LINEAR_MAJOR_RESOLUTION 10
// min. and max. vertical velocity
// The altitude difference between top and bottom of scale
#define ALTIMETER_PROJECTED_SPAN 50
// every 5 meters there is a tick mark
#define ALTIMETER_PROJECTED_RESOLUTION 5
// every 10 meters there is a number
#define ALTIMETER_PROJECTED_MAJOR_RESOLUTION 10
// min. and max. vertical velocity
//#define ALTIMETER_PROJECTED
#define ALTIMETER_VVI_SPAN 10
#define ALTIMETER_VVI_LOGARITHMIC true
#define SHOW_ZERO_ON_SCALES true
#define SCALE_TEXT_SIZE 0.042
#define SMALL_TEXT_SIZE 0.035
#define UNKNOWN_BATTERY -1
class PrimaryFlightDisplay : public QWidget
{
Q_OBJECT
public:
PrimaryFlightDisplay(int width = 640, int height = 480, QWidget* parent = NULL);
~PrimaryFlightDisplay();
/** @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 */
void updateAttitude(UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp);
// void updateAttitudeThrustSetPoint(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec);
void updateBattery(UASInterface*, double, double, int);
void receiveHeartbeat(UASInterface*);
void updateThrust(UASInterface*, double);
void updateLocalPosition(UASInterface*,double,double,double,quint64);
void updateGlobalPosition(UASInterface*,double,double,double,quint64);
void updateSpeed(UASInterface*,double,double,double,quint64);
void updateState(UASInterface*,QString);
void updateMode(int id,QString mode, QString description);
void updateLoad(UASInterface*, double);
void selectWaypoint(int uasId, int id);
void paintEvent(QPaintEvent *event);
void resizeEvent(QResizeEvent *e);
// from HUD.h:
/** @brief Preferred Size */
QSize sizeHint() const;
/** @brief Start updating widget */
void showEvent(QShowEvent* event);
/** @brief Stop updating widget */
void hideEvent(QHideEvent* event);
// dongfang: We have no context menu. Viewonly.
// void contextMenuEvent (QContextMenuEvent* event);
// dongfang: What is that?
void createActions();
static const int updateInterval = 40;
public slots:
/** @brief Set the currently monitored UAS */
virtual void setActiveUAS(UASInterface* uas);
protected slots:
void paintOnTimer();
signals:
void visibilityChanged(bool visible);
private:
//void prepareTransform(QPainter& painter, qreal width, qreal height);
//void transformToGlobalSystem(QPainter& painter, qreal width, qreal height, float roll, float pitch);
void drawTextCenter(QPainter& painter, QString text, float fontSize, float x, float y);
void drawTextLeftCenter(QPainter& painter, QString text, float fontSize, float x, float y);
void drawTextRightCenter(QPainter& painter, QString text, float fontSize, float x, float y);
void drawTextCenterBottom(QPainter& painter, QString text, float fontSize, float x, float y);
void drawTextCenterTop(QPainter& painter, QString text, float fontSize, float x, float y);
void drawAIGlobalFeatures(QPainter& painter, QRectF area);
void drawAIAirframeFixedFeatures(QPainter& painter, QRectF area);
void drawPitchScale(QPainter& painter, QRectF area, bool drawNumbersLeft, bool drawNumbersRight);
void drawRollScale(QPainter& painter, QRectF area, bool drawTicks, bool drawNumbers);
void drawAIAttitudeScales(QPainter& painter, QRectF area);
#if defined(USE_DISK_COMPASS) || defined(USE_DISK2_COMPASS)
void drawCompassDisk(QPainter& painter, QRectF area);
#else
void drawCompassTape(QPainter& painter, QRectF area, float yaw);
#endif
void drawAltimeter(QPainter& painter, QRectF area, float altitude, float maxAltitude, float vv);
void fillInstrumentBackground(QPainter& painter, QRectF edge);
void drawInstrumentBackground(QPainter& painter, QRectF edge);
void drawLinkStatsPanel(QPainter& painter, QRectF area);
void drawSysStatsPanel(QPainter& painter, QRectF area);
void drawMissionStatsPanel(QPainter& painter, QRectF area);
void drawSensorsStatsPanel(QPainter& painter, QRectF area);
void makeDummyData();
void doPaint();
void paintAllInOne();
void paintSeparate();
float roll;
float pitch;
float heading;
// APM: GPS and baro mix. From the GLOBAL_POSITION_INT or VFR_HUD messages.
float aboveASLAltitude;
float GPSAltitude;
// APM: GPS and baro mix above home (GPS) altitude. This value comes from the GLOBAL_POSITION_INT message.
// Do !!!NOT!!! ever do altitude calculations at the ground station. There are enough pitfalls already.
// The MP "set home altitude" button will not be repeated here if it did that.
float aboveHomeAltitude;
float groundSpeed;
float airSpeed;
QString mode;
QString state;
float load;
QPen whitePen;
QPen redPen;
QPen amberPen;
QPen greenPen;
QPen blackPen;
QPen instrumentEdgePen;
QBrush instrumentBackground;
QBrush HUDInstrumentBackground;
QFont font;
QTimer* refreshTimer; ///< The main timer, controls the update rate
UASInterface* uas; ///< The uas currently monitored
//QString energyStatus; ///< Current fuel level / battery voltage
double batteryVoltage;
double batteryCharge;
static const int tickValues[];
static const QString compassWindNames[];
signals:
public slots:
};
#endif // PRIMARYFLIGHTDISPLAY_H

6
src/ui/QGCRGBDView.cc

@ -6,7 +6,7 @@
#include "UASManager.h" #include "UASManager.h"
QGCRGBDView::QGCRGBDView(int width, int height, QWidget *parent) : QGCRGBDView::QGCRGBDView(int width, int height, QWidget *parent) :
HUD(width, height, parent), HUD_old(width, height, parent),
rgbEnabled(false), rgbEnabled(false),
depthEnabled(false) depthEnabled(false)
{ {
@ -70,7 +70,7 @@ void QGCRGBDView::setActiveUAS(UASInterface* uas)
connect(uas, SIGNAL(rgbdImageChanged(UASInterface*)), this, SLOT(updateData(UASInterface*))); connect(uas, SIGNAL(rgbdImageChanged(UASInterface*)), this, SLOT(updateData(UASInterface*)));
} }
HUD::setActiveUAS(uas); HUD_old::setActiveUAS(uas);
} }
void QGCRGBDView::clearData(void) void QGCRGBDView::clearData(void)
@ -85,7 +85,7 @@ void QGCRGBDView::contextMenuEvent(QContextMenuEvent* event)
{ {
QMenu menu(this); QMenu menu(this);
// Update actions // Update actions
enableHUDAction->setChecked(hudInstrumentsEnabled); enableHUDAction->setChecked(HUDInstrumentsEnabled);
//enableVideoAction->setChecked(videoEnabled); //enableVideoAction->setChecked(videoEnabled);
enableRGBAction->setChecked(rgbEnabled); enableRGBAction->setChecked(rgbEnabled);
enableDepthAction->setChecked(depthEnabled); enableDepthAction->setChecked(depthEnabled);

2
src/ui/QGCRGBDView.h

@ -3,7 +3,7 @@
#include "HUD.h" #include "HUD.h"
class QGCRGBDView : public HUD class QGCRGBDView : public HUD_old
{ {
Q_OBJECT Q_OBJECT
public: public:

Loading…
Cancel
Save