Newer
Older
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Head Up Display (HUD)
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QShowEvent>
pixhawk
committed
#include <QContextMenuEvent>
#include <QMenu>
#include <QDesktopServices>
#include <QFileDialog>
pixhawk
committed
#include "UAS.h"
#include "QGC.h"
// Fix for some platforms, e.g. windows
#ifndef GL_MULTISAMPLE
#define GL_MULTISAMPLE 0x809D
#endif
template<typename T>
inline bool isnan(T value)
{
}
// requires #include <limits>
template<typename T>
inline bool isinf(T value)
{
return std::numeric_limits<T>::has_infinity && (value == std::numeric_limits<T>::infinity() || (-1*value) == std::numeric_limits<T>::infinity());
}
/**
* @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::HUD(int width, int height, QWidget* parent)
: QGLWidget(QGLFormat(QGL::SampleBuffers), parent),
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
uas(NULL),
yawInt(0.0f),
mode(tr("UNKNOWN MODE")),
state(tr("UNKNOWN STATE")),
fuelStatus(tr("00.0V (00m:00s)")),
xCenterOffset(0.0f),
yCenterOffset(0.0f),
vwidth(200.0f),
vheight(150.0f),
vGaugeSpacing(50.0f),
vPitchPerDeg(6.0f), ///< 4 mm y translation per degree)
rawBuffer1(NULL),
rawBuffer2(NULL),
rawImage(NULL),
rawLastIndex(0),
rawExpectedBytes(0),
bytesPerLine(1),
imageStarted(false),
receivedDepth(8),
receivedChannels(1),
receivedWidth(640),
receivedHeight(480),
defaultColor(QColor(70, 200, 70)),
setPointColor(QColor(200, 20, 200)),
warningColor(Qt::yellow),
criticalColor(Qt::red),
infoColor(QColor(20, 200, 20)),
fuelColor(criticalColor),
warningBlinkRate(5),
refreshTimer(new QTimer(this)),
noCamera(true),
hardwareAcceleration(true),
strongStrokeWidth(1.5f),
normalStrokeWidth(1.0f),
fineStrokeWidth(0.5f),
waypointName(""),
roll(0.0f),
pitch(0.0f),
yaw(0.0f),
rollLP(0.0f),
pitchLP(0.0f),
yawLP(0.0f),
yawDiff(0.0f),
xPos(0.0),
yPos(0.0),
zPos(0.0),
xSpeed(0.0),
ySpeed(0.0),
zSpeed(0.0),
lastSpeedUpdate(0),
totalSpeed(0.0),
totalAcc(0.0),
lat(0.0),
lon(0.0),
alt(0.0),
load(0.0f),
offlineDirectory(""),
nextOfflineImage(""),
hudInstrumentsEnabled(true),
videoEnabled(false),
xImageFactor(1.0),
pixhawk
committed
yImageFactor(1.0),
imageRequested(false)
{
// Set auto fill to false
setAutoFillBackground(false);
// Set minimum size
setMinimumSize(80, 60);
// Set preferred size
setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
// Fill with black background
QImage fill = QImage(width, height, QImage::Format_Indexed8);
fill.setNumColors(3);
fill.setColor(0, qRgb(0, 0, 0));
fill.setColor(1, qRgb(0, 0, 0));
fill.setColor(2, qRgb(0, 0, 0));
fill.fill(0);
//QString imagePath = "/Users/user/Desktop/frame0000.png";
//qDebug() << __FILE__ << __LINE__ << "template image:" << imagePath;
//fill = QImage(imagePath);
refreshTimer->setInterval(updateInterval);
connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD()));
//glDrawPixels(glImage.width(), glImage.height(), GL_RGBA, GL_UNSIGNED_BYTE, glImage.bits());
// Set size once
//setFixedSize(fill.size());
//setMinimumSize(fill.size());
//setMaximumSize(fill.size());
// Lock down the size
//setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed));
fontDatabase = QFontDatabase();
const QString fontFileName = ":/general/vera.ttf"; ///< Font file is part of the QRC file and compiled into the app
const QString fontFamilyName = "Bitstream Vera Sans";
if(!QFile::exists(fontFileName)) qDebug() << "ERROR! font file: " << fontFileName << " DOES NOT EXIST!";
fontDatabase.addApplicationFont(fontFileName);
font = fontDatabase.font(fontFamilyName, "Roman", qMax(5,(int)(10.0f*scalingFactor*1.2f+0.5f)));
QFont* fontPtr = &font;
if (font.family() != fontFamilyName) qDebug() << "ERROR! WRONG FONT LOADED: " << fontFamilyName;
}
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
pixhawk
committed
createActions();
if (UASManager::instance()->getActiveUAS() != NULL) setActiveUAS(UASManager::instance()->getActiveUAS());
QSize HUD::sizeHint() const
{
lm
committed
return QSize(width(), (width()*3.0f)/4);
}
void HUD::showEvent(QShowEvent* event)
{
// React only to internal (pre-display)
// events
Q_UNUSED(event)
refreshTimer->start(updateInterval);
}
void HUD::hideEvent(QHideEvent* event)
{
// React only to internal (pre-display)
// events
Q_UNUSED(event);
refreshTimer->stop();
pixhawk
committed
void HUD::contextMenuEvent (QContextMenuEvent* event)
{
QMenu menu(this);
// Update actions
enableHUDAction->setChecked(hudInstrumentsEnabled);
enableVideoAction->setChecked(videoEnabled);
pixhawk
committed
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
menu.addAction(enableHUDAction);
//menu.addAction(selectHUDColorAction);
menu.addAction(enableVideoAction);
menu.addAction(selectOfflineDirectoryAction);
//menu.addAction(selectVideoChannelAction);
menu.exec(event->globalPos());
}
void HUD::createActions()
{
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)));
enableVideoAction = new QAction(tr("Enable Video Live feed"), this);
enableVideoAction->setStatusTip(tr("Show the video live feed"));
enableVideoAction->setCheckable(true);
enableVideoAction->setChecked(videoEnabled);
connect(enableVideoAction, SIGNAL(triggered(bool)), this, SLOT(enableVideo(bool)));
selectOfflineDirectoryAction = new QAction(tr("Select image log"), this);
selectOfflineDirectoryAction->setStatusTip(tr("Load previously logged images into simulation / replay"));
connect(selectOfflineDirectoryAction, SIGNAL(triggered()), this, SLOT(selectOfflineDirectory()));
}
/**
*
* @param uas the UAS/MAV to monitor/display with the HUD
*/
void HUD::setActiveUAS(UASInterface* uas)
{
disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64)));
disconnect(this->uas, SIGNAL(batteryChanged(UASInterface*, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, int)));
disconnect(this->uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString)));
disconnect(this->uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
disconnect(this->uas, SIGNAL(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*)));
disconnect(this->uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int)));
pixhawk
committed
// Try to disconnect the image link
UAS* u = dynamic_cast<UAS*>(this->uas);
pixhawk
committed
disconnect(u, SIGNAL(imageStarted(quint64)), this, SLOT(startImage(quint64)));
disconnect(u, SIGNAL(imageReady(UASInterface*)), this, SLOT(copyImage()));
pixhawk
committed
}
}
pixhawk
committed
// Now connect the new UAS
// Setup communication
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64)));
connect(uas, SIGNAL(batteryChanged(UASInterface*, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, int)));
connect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString)));
connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
connect(uas, SIGNAL(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*)));
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
pixhawk
committed
connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int, int)));
// Try to connect the image link
UAS* u = dynamic_cast<UAS*>(uas);
pixhawk
committed
connect(u, SIGNAL(imageStarted(quint64)), this, SLOT(startImage(quint64)));
connect(u, SIGNAL(imageReady(UASInterface*)), this, SLOT(copyImage()));
pixhawk
committed
}
pixhawk
committed
// Set new UAS
this->uas = uas;
this->u = dynamic_cast<UAS*>(this->uas);
pixhawk
committed
}
//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);
//// updateValue(uas, "yaw desired", yawDesired, msec);
//// updateValue(uas, "thrust desired", thrustDesired, msec);
//}
void HUD::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp)
{
Q_UNUSED(uas);
Q_UNUSED(timestamp);
this->roll = roll;
this->pitch = pitch;
this->yaw = yaw;
}
void HUD::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{
fuelStatus = tr("BAT [%1% | %2V] (%3:%4)").arg(percent, 2, 'f', 0, QChar('0')).arg(voltage, 4, 'f', 1, QChar('0')).arg(seconds/60, 2, 10, QChar('0')).arg(seconds%60, 2, 10, QChar('0'));
fuelColor = infoColor;
}
}
void HUD::receiveHeartbeat(UASInterface*)
{
}
void HUD::updateThrust(UASInterface* uas, double thrust)
Q_UNUSED(uas);
Q_UNUSED(thrust);
// updateValue(uas, "thrust", thrust, MG::TIME::getGroundTimeNow());
}
void HUD::updateLocalPosition(UASInterface* uas,double x,double y,double z,quint64 timestamp)
{
Q_UNUSED(uas);
Q_UNUSED(timestamp);
this->xPos = x;
this->yPos = y;
this->zPos = z;
void HUD::updateGlobalPosition(UASInterface* uas,double lat, double lon, double altitude, quint64 timestamp)
Q_UNUSED(uas);
Q_UNUSED(timestamp);
this->lat = lat;
this->lon = lon;
this->alt = altitude;
}
void HUD::updateSpeed(UASInterface* uas,double x,double y,double z,quint64 timestamp)
{
Q_UNUSED(uas);
Q_UNUSED(timestamp);
this->xSpeed = x;
this->ySpeed = y;
this->zSpeed = z;
double newTotalSpeed = sqrt(xSpeed*xSpeed + ySpeed*ySpeed + zSpeed*zSpeed);
totalAcc = (newTotalSpeed - totalSpeed) / ((double)(lastSpeedUpdate - timestamp)/1000.0);
totalSpeed = newTotalSpeed;
}
/**
* 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
*/
void HUD::updateState(UASInterface* uas,QString state)
// Only one UAS is connected at a time
Q_UNUSED(uas);
this->state = 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
*/
void HUD::updateMode(int id,QString mode, QString description)
// Only one UAS is connected at a time
Q_UNUSED(id);
Q_UNUSED(description);
}
void HUD::updateLoad(UASInterface* uas, double load)
{
Q_UNUSED(uas);
this->load = load;
//updateValue(uas, "load", load, MG::TIME::getGroundTimeNow());
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
}
/**
* @param y coordinate in pixels to be converted to reference mm units
* @return the screen coordinate relative to the QGLWindow origin
*/
float HUD::refToScreenX(float x)
{
//qDebug() << "sX: " << (scalingFactor * x);
return (scalingFactor * x);
}
/**
* @param x coordinate in pixels to be converted to reference mm units
* @return the screen coordinate relative to the QGLWindow origin
*/
float HUD::refToScreenY(float y)
{
//qDebug() << "sY: " << (scalingFactor * y);
return (scalingFactor * y);
}
/**
* This functions works in the OpenGL view, which is already translated by
* the x and y center offsets.
*
*/
void HUD::paintCenterBackground(float roll, float pitch, float yaw)
{
// Center indicator is 100 mm wide
float referenceWidth = 70.0;
float referenceHeight = 70.0;
// HUD is assumed to be 200 x 150 mm
// so that positions can be hardcoded
// but can of course be scaled.
double referencePositionX = vwidth / 2.0 - referenceWidth/2.0;
double referencePositionY = vheight / 2.0 - referenceHeight/2.0;
//this->width()/2.0+(xCenterOffset*scalingFactor), this->height()/2.0+(yCenterOffset*scalingFactor);
setupGLView(referencePositionX, referencePositionY, referenceWidth, referenceHeight);
// Store current position in the model view
// the position will be restored after drawing
glMatrixMode(GL_MODELVIEW);
glPushMatrix();
// Move to the center of the window
glTranslatef(referenceWidth/2.0f,referenceHeight/2.0f,0);
// Move based on the yaw difference
glTranslatef(yaw, 0.0f, 0.0f);
glRotatef((roll/M_PI)*180.0f, 0.0f, 0.0f, 1.0f);
// Translate in the direction of the rotation based
// on the pitch. On the 777, a pitch of 1 degree = 2 mm
//glTranslatef(0, ((-pitch/M_PI)*180.0f * vPitchPerDeg), 0);
glTranslatef(0.0f, (-pitch * vPitchPerDeg * 16.5f), 0.0f);
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
// Ground
glColor3ub(179,102,0);
glBegin(GL_POLYGON);
glVertex2f(-300,-300);
glVertex2f(-300,0);
glVertex2f(300,0);
glVertex2f(300,-300);
glVertex2f(-300,-300);
glEnd();
// Sky
glColor3ub(0,153,204);
glBegin(GL_POLYGON);
glVertex2f(-300,0);
glVertex2f(-300,300);
glVertex2f(300,300);
glVertex2f(300,0);
glVertex2f(-300,0);
glEnd();
}
/**
* Paint text on top of the image and OpenGL drawings
*
* @param text chars to write
* @param color text color
* @param fontSize text size in mm
* @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::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);
float pPositionY = refToScreenY(refY) - (fontSize*scalingFactor*0.212f);
QFont font("Bitstream Vera Sans");
// Enforce minimum font size of 5 pixels
int fSize = qMax(5, (int)(fontSize*scalingFactor*1.26f));
font.setPixelSize(fSize);
QFontMetrics metrics = QFontMetrics(font);
int border = qMax(4, metrics.leading());
QRect rect = metrics.boundingRect(0, 0, width() - 2*border, int(height()*0.125),
Qt::AlignLeft | Qt::TextWordWrap, text);
painter->setPen(color);
painter->setFont(font);
painter->setRenderHint(QPainter::TextAntialiasing);
painter->drawText(pPositionX, pPositionY,
rect.width(), rect.height(),
Qt::AlignCenter | Qt::TextWordWrap, text);
painter->setPen(prevPen);
}
void HUD::initializeGL()
{
bool antialiasing = true;
// Antialiasing setup
glEnable(GL_BLEND);
glBlendFunc(GL_SRC_ALPHA,GL_ONE_MINUS_SRC_ALPHA);
glEnable(GL_POINT_SMOOTH);
glEnable(GL_LINE_SMOOTH);
glHint(GL_POINT_SMOOTH_HINT, GL_NICEST);
glHint(GL_LINE_SMOOTH_HINT, GL_NICEST);
glDisable(GL_BLEND);
glDisable(GL_POINT_SMOOTH);
glDisable(GL_LINE_SMOOTH);
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
}
}
/**
* @param referencePositionX horizontal position in the reference mm-unit space
* @param referencePositionY horizontal position in the reference mm-unit space
* @param referenceWidth 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)
{
int pixelWidth = (int)(referenceWidth * scalingFactor);
int pixelHeight = (int)(referenceHeight * scalingFactor);
// Translate and scale the GL view in the virtual reference coordinate units on the screen
int pixelPositionX = (int)((referencePositionX * scalingFactor) + xCenterOffset);
int pixelPositionY = this->height() - (referencePositionY * scalingFactor) + yCenterOffset - pixelHeight;
//qDebug() << "Pixel x" << pixelPositionX << "pixelY" << pixelPositionY;
//qDebug() << "xCenterOffset:" << xCenterOffset << "yCenterOffest" << yCenterOffset
//The viewport is established at the correct pixel position and clips everything
// out of the desired instrument location
glViewport(pixelPositionX, pixelPositionY, pixelWidth, pixelHeight);
glMatrixMode(GL_PROJECTION);
glLoadIdentity();
// The ortho projection is setup in a way that so that the drawing is done in the
// reference coordinate space
glOrtho(0, referenceWidth, 0, referenceHeight, -1, 1);
glMatrixMode(GL_MODELVIEW);
glLoadIdentity();
//glScalef(scaleX, scaleY, 1.0f);
}
void HUD::paintRollPitchStrips()
{
}
// the event is ignored as this widget
// is refreshed automatically
}
void HUD::paintHUD()
{
// static quint64 interval = 0;
// qDebug() << "INTERVAL:" << MG::TIME::getGroundTimeNow() - interval << __FILE__ << __LINE__;
// interval = MG::TIME::getGroundTimeNow();
#if (QGC_EVENTLOOP_DEBUG)
qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
// Read out most important values to limit hash table lookups
// Low-pass roll, pitch and yaw
rollLP = rollLP * 0.2f + 0.8f * roll;
pitchLP = pitchLP * 0.2f + 0.8f * pitch;
yawLP = yawLP * 0.2f + 0.8f * yaw;
// Translate for yaw
const float maxYawTrans = 60.0f;
float newYawDiff = yawDiff;
if (isinf(newYawDiff)) newYawDiff = yawDiff;
if (newYawDiff > M_PI) newYawDiff = newYawDiff - M_PI;
if (newYawDiff < -M_PI) newYawDiff = newYawDiff + M_PI;
newYawDiff = yawDiff * 0.8 + newYawDiff * 0.2;
if (yawInt > M_PI) yawInt = (float)M_PI;
if (yawInt < -M_PI) yawInt = (float)-M_PI;
float yawTrans = yawInt * (float)maxYawTrans;
if ((yawTrans < 5.0) && (yawTrans > -5.0)) yawTrans = 0;
// Negate to correct direction
yawTrans = -yawTrans;
//qDebug() << "yaw translation" << yawTrans << "integral" << yawInt << "difference" << yawDiff << "yaw" << yaw;
// Update scaling factor
// adjust scaling to fit both horizontally and vertically
scalingFactor = this->width()/vwidth;
double scalingFactorH = this->height()/vheight;
if (scalingFactorH < scalingFactor) scalingFactor = scalingFactorH;
// OPEN GL PAINTING
// Store model view matrix to be able to reset it to the previous state
makeCurrent();
glMatrixMode(GL_MODELVIEW);
glPushMatrix();
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
// Fill with black background
if (videoEnabled) {
if (nextOfflineImage != "" && QFileInfo(nextOfflineImage).exists()) {
pixhawk
committed
qDebug() << __FILE__ << __LINE__ << "template image:" << nextOfflineImage;
QImage fill = QImage(nextOfflineImage);
pixhawk
committed
glImage = QGLWidget::convertToGLFormat(fill);
pixhawk
committed
// Reset to save load efforts
nextOfflineImage = "";
}
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
glDrawPixels(glImage.width(), glImage.height(), GL_RGBA, GL_UNSIGNED_BYTE, glImage.bits());
pixhawk
committed
// Blue / brown background
paintCenterBackground(roll, pitch, yawTrans);
}
glMatrixMode(GL_MODELVIEW);
glPopMatrix();
// END OF OPENGL PAINTING
pixhawk
committed
//glEnable(GL_MULTISAMPLE);
// QT PAINTING
//makeCurrent();
QPainter painter;
painter.begin(this);
painter.setRenderHint(QPainter::Antialiasing, true);
painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
painter.translate((this->vwidth/2.0+xCenterOffset)*scalingFactor, (this->vheight/2.0+yCenterOffset)*scalingFactor);
// COORDINATE FRAME IS NOW (0,0) at CENTER OF WIDGET
// Draw all fixed indicators
// MODE
paintText(mode, infoColor, 2.0f, (-vwidth/2.0) + 10, -vheight/2.0 + 10, &painter);
// STATE
paintText(state, infoColor, 2.0f, (-vwidth/2.0) + 10, -vheight/2.0 + 15, &painter);
// BATTERY
paintText(fuelStatus, fuelColor, 2.0f, (-vwidth/2.0) + 10, -vheight/2.0 + 20, &painter);
// Waypoint
paintText(waypointName, defaultColor, 2.0f, (-vwidth/3.0) + 10, +vheight/3.0 + 15, &painter);
pixhawk
committed
// YAW INDICATOR
//
// .
// . .
// .......
//
const float yawIndicatorWidth = 4.0f;
const float yawIndicatorY = vheight/2.0f - 10.0f;
QPolygon yawIndicator(4);
yawIndicator.setPoint(0, QPoint(refToScreenX(0.0f), refToScreenY(yawIndicatorY)));
yawIndicator.setPoint(1, QPoint(refToScreenX(yawIndicatorWidth/2.0f), refToScreenY(yawIndicatorY+yawIndicatorWidth)));
yawIndicator.setPoint(2, QPoint(refToScreenX(-yawIndicatorWidth/2.0f), refToScreenY(yawIndicatorY+yawIndicatorWidth)));
yawIndicator.setPoint(3, QPoint(refToScreenX(0.0f), refToScreenY(yawIndicatorY)));
painter.setPen(defaultColor);
painter.drawPolyline(yawIndicator);
pixhawk
committed
// CENTER
pixhawk
committed
// HEADING INDICATOR
//
// __ __
// \/\/
//
const float hIndicatorWidth = 7.0f;
const float hIndicatorY = -25.0f;
const float hIndicatorYLow = hIndicatorY + hIndicatorWidth / 6.0f;
const float hIndicatorSegmentWidth = hIndicatorWidth / 7.0f;
QPolygon hIndicator(7);
hIndicator.setPoint(0, QPoint(refToScreenX(0.0f-hIndicatorWidth/2.0f), refToScreenY(hIndicatorY)));
hIndicator.setPoint(1, QPoint(refToScreenX(0.0f-hIndicatorWidth/2.0f+hIndicatorSegmentWidth*1.75f), refToScreenY(hIndicatorY)));
hIndicator.setPoint(2, QPoint(refToScreenX(0.0f-hIndicatorSegmentWidth*1.0f), refToScreenY(hIndicatorYLow)));
hIndicator.setPoint(3, QPoint(refToScreenX(0.0f), refToScreenY(hIndicatorY)));
hIndicator.setPoint(4, QPoint(refToScreenX(0.0f+hIndicatorSegmentWidth*1.0f), refToScreenY(hIndicatorYLow)));
hIndicator.setPoint(5, QPoint(refToScreenX(0.0f+hIndicatorWidth/2.0f-hIndicatorSegmentWidth*1.75f), refToScreenY(hIndicatorY)));
hIndicator.setPoint(6, QPoint(refToScreenX(0.0f+hIndicatorWidth/2.0f), refToScreenY(hIndicatorY)));
painter.setPen(defaultColor);
painter.drawPolyline(hIndicator);
pixhawk
committed
// SETPOINT
const float centerWidth = 4.0f;
painter.setPen(defaultColor);
painter.setBrush(Qt::NoBrush);
// TODO
//painter.drawEllipse(QPointF(refToScreenX(qMin(10.0f, values.value("roll desired", 0.0f) * 10.0f)), refToScreenY(qMin(10.0f, values.value("pitch desired", 0.0f) * 10.0f))), refToScreenX(centerWidth/2.0f), refToScreenX(centerWidth/2.0f));
pixhawk
committed
const float centerCrossWidth = 10.0f;
// left
painter.drawLine(QPointF(refToScreenX(-centerWidth / 2.0f), refToScreenY(0.0f)), QPointF(refToScreenX(-centerCrossWidth / 2.0f), refToScreenY(0.0f)));
// right
painter.drawLine(QPointF(refToScreenX(centerWidth / 2.0f), refToScreenY(0.0f)), QPointF(refToScreenX(centerCrossWidth / 2.0f), refToScreenY(0.0f)));
// top
painter.drawLine(QPointF(refToScreenX(0.0f), refToScreenY(-centerWidth / 2.0f)), QPointF(refToScreenX(0.0f), refToScreenY(-centerCrossWidth / 2.0f)));
pixhawk
committed
// COMPASS
const float compassY = -vheight/2.0f + 10.0f;
QRectF compassRect(QPointF(refToScreenX(-5.0f), refToScreenY(compassY)), QSizeF(refToScreenX(10.0f), refToScreenY(5.0f)));
painter.setBrush(Qt::NoBrush);
painter.setPen(Qt::SolidLine);
painter.setPen(defaultColor);
painter.drawRoundedRect(compassRect, 2, 2);
QString yawAngle;
pixhawk
committed
// const float yawDeg = ((values.value("yaw", 0.0f)/M_PI)*180.0f)+180.f;
pixhawk
committed
// YAW is in compass-human readable format, so 0 - 360deg. This is normal in aviation, not -180 - +180.
const float yawDeg = ((yawLP/M_PI)*180.0f)+180.0f+180.0f;
int yawCompass = static_cast<int>(yawDeg) % 360;
yawAngle.sprintf("%03d", yawCompass);
paintText(yawAngle, defaultColor, 3.5f, -4.3f, compassY+ 0.97f, &painter);
pixhawk
committed
// CHANGE RATE STRIPS
drawChangeRateStrip(-51.0f, -50.0f, 15.0f, -1.0f, 1.0f, -zSpeed, &painter);
pixhawk
committed
// CHANGE RATE STRIPS
drawChangeRateStrip(49.0f, -50.0f, 15.0f, -1.0f, 1.0f, totalAcc, &painter);
pixhawk
committed
// GAUGES
pixhawk
committed
// Left altitude gauge
gaugeAltitude = -zPos;
}
drawChangeIndicatorGauge(-vGaugeSpacing, -15.0f, 10.0f, 2.0f, gaugeAltitude, defaultColor, &painter, false);
pixhawk
committed
// Right speed gauge
drawChangeIndicatorGauge(vGaugeSpacing, -15.0f, 10.0f, 5.0f, totalSpeed, defaultColor, &painter, false);
pixhawk
committed
// Waypoint name
if (waypointName != "") paintText(waypointName, defaultColor, 2.0f, (-vwidth/3.0) + 10, +vheight/3.0 + 15, &painter);
// MOVING PARTS
painter.translate(refToScreenX(yawTrans), 0);
// Rotate view and draw all roll-dependent indicators
painter.rotate((rollLP/M_PI)* -180.0f);
painter.translate(0, (-pitchLP/(float)M_PI)* -180.0f * refToScreenY(1.8f));
pixhawk
committed
//qDebug() << "ROLL" << roll << "PITCH" << pitch << "YAW DIFF" << valuesDot.value("roll", 0.0f);
// PITCH
pixhawk
committed
paintPitchLines(pitchLP, &painter);
painter.end();
pixhawk
committed
QPainter painter;
painter.begin(this);
painter.end();
}
pixhawk
committed
}
/*
void HUD::paintGL()
{
static float roll = 0.0;
static float pitch = 0.0;
static float yaw = 0.0;
// Read out most important values to limit hash table lookups
roll = roll * 0.5 + 0.5 * values.value("roll", 0.0f);
pitch = pitch * 0.5 + 0.5 * values.value("pitch", 0.0f);
yaw = yaw * 0.5 + 0.5 * values.value("yaw", 0.0f);
//qDebug() << __FILE__ << __LINE__ << "ROLL:" << roll << "PITCH:" << pitch << "YAW:" << yaw;
// Update scaling factor
// adjust scaling to fit both horizontally and vertically
scalingFactor = this->width()/vwidth;
double scalingFactorH = this->height()/vheight;
if (scalingFactorH < scalingFactor) scalingFactor = scalingFactorH;
glClear(GL_COLOR_BUFFER_BIT);
//if(!noCamera) glDrawPixels(glImage.width(), glImage.height(), GL_RGBA, GL_UNSIGNED_BYTE, glImage.bits());
//glDrawPixels(glImage.width(), glImage.height(), GL_RGBA, GL_UNSIGNED_BYTE, glImage.bits()); // FIXME Remove after testing
// Blue / Brown background
if (noCamera) paintCenterBackground(roll, pitch, yaw);
// // Store current GL model view
// glMatrixMode(GL_MODELVIEW);
// glPushMatrix();
//
// // Setup GL view
// setupGLView(0.0f, 0.0f, vwidth, vheight);
//
// // Restore previous view
// glPopMatrix();
// Now draw QPainter overlay
//painter.setRenderHint(QPainter::Antialiasing);
// Position the coordinate frame according to the setup
//painter.setRenderHint(QPainter::Antialiasing, true);
painter.translate((this->vwidth/2.0+xCenterOffset)*scalingFactor, (this->vheight/2.0+yCenterOffset)*scalingFactor);
// COORDINATE FRAME IS NOW (0,0) at CENTER OF WIDGET
// Draw all fixed indicators
// MODE
paintText(mode, infoColor, 2.0f, (-vwidth/2.0) + 10, -vheight/2.0 + 10, &painter);
// STATE
paintText(state, infoColor, 2.0f, (-vwidth/2.0) + 10, -vheight/2.0 + 15, &painter);
paintText(fuelStatus, fuelColor, 2.0f, (-vwidth/2.0) + 10, -vheight/2.0 + 20, &painter);
// Waypoint
paintText(waypointName, defaultColor, 2.0f, (-vwidth/3.0) + 10, +vheight/3.0 + 15, &painter);
// YAW INDICATOR
//
// .
// . .
// .......
//
const float yawIndicatorWidth = 4.0f;
const float yawIndicatorY = vheight/2.0f - 10.0f;
QPolygon yawIndicator(4);
yawIndicator.setPoint(0, QPoint(refToScreenX(0.0f), refToScreenY(yawIndicatorY)));
yawIndicator.setPoint(1, QPoint(refToScreenX(yawIndicatorWidth/2.0f), refToScreenY(yawIndicatorY+yawIndicatorWidth)));
yawIndicator.setPoint(2, QPoint(refToScreenX(-yawIndicatorWidth/2.0f), refToScreenY(yawIndicatorY+yawIndicatorWidth)));
yawIndicator.setPoint(3, QPoint(refToScreenX(0.0f), refToScreenY(yawIndicatorY)));
painter.setPen(defaultColor);
painter.drawPolyline(yawIndicator);
// HEADING INDICATOR
//
// __ __
// \/\/
//
const float hIndicatorWidth = 7.0f;
const float hIndicatorY = -25.0f;
const float hIndicatorYLow = hIndicatorY + hIndicatorWidth / 6.0f;
const float hIndicatorSegmentWidth = hIndicatorWidth / 7.0f;
QPolygon hIndicator(7);
hIndicator.setPoint(0, QPoint(refToScreenX(0.0f-hIndicatorWidth/2.0f), refToScreenY(hIndicatorY)));
hIndicator.setPoint(1, QPoint(refToScreenX(0.0f-hIndicatorWidth/2.0f+hIndicatorSegmentWidth*1.75f), refToScreenY(hIndicatorY)));
hIndicator.setPoint(2, QPoint(refToScreenX(0.0f-hIndicatorSegmentWidth*1.0f), refToScreenY(hIndicatorYLow)));
hIndicator.setPoint(3, QPoint(refToScreenX(0.0f), refToScreenY(hIndicatorY)));
hIndicator.setPoint(4, QPoint(refToScreenX(0.0f+hIndicatorSegmentWidth*1.0f), refToScreenY(hIndicatorYLow)));
hIndicator.setPoint(5, QPoint(refToScreenX(0.0f+hIndicatorWidth/2.0f-hIndicatorSegmentWidth*1.75f), refToScreenY(hIndicatorY)));
hIndicator.setPoint(6, QPoint(refToScreenX(0.0f+hIndicatorWidth/2.0f), refToScreenY(hIndicatorY)));
painter.setPen(defaultColor);
painter.drawPolyline(hIndicator);
// SETPOINT
const float centerWidth = 4.0f;
painter.setPen(defaultColor);
painter.setBrush(Qt::NoBrush);
// TODO
//painter.drawEllipse(QPointF(refToScreenX(qMin(10.0f, values.value("roll desired", 0.0f) * 10.0f)), refToScreenY(qMin(10.0f, values.value("pitch desired", 0.0f) * 10.0f))), refToScreenX(centerWidth/2.0f), refToScreenX(centerWidth/2.0f));
const float centerCrossWidth = 10.0f;
// left
painter.drawLine(QPointF(refToScreenX(-centerWidth / 2.0f), refToScreenY(0.0f)), QPointF(refToScreenX(-centerCrossWidth / 2.0f), refToScreenY(0.0f)));
// right
painter.drawLine(QPointF(refToScreenX(centerWidth / 2.0f), refToScreenY(0.0f)), QPointF(refToScreenX(centerCrossWidth / 2.0f), refToScreenY(0.0f)));
// top
painter.drawLine(QPointF(refToScreenX(0.0f), refToScreenY(-centerWidth / 2.0f)), QPointF(refToScreenX(0.0f), refToScreenY(-centerCrossWidth / 2.0f)));
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
// COMPASS
const float compassY = -vheight/2.0f + 10.0f;
QRectF compassRect(QPointF(refToScreenX(-5.0f), refToScreenY(compassY)), QSizeF(refToScreenX(10.0f), refToScreenY(5.0f)));
painter.setBrush(Qt::NoBrush);
painter.setPen(Qt::SolidLine);
painter.setPen(defaultColor);
painter.drawRoundedRect(compassRect, 2, 2);
QString yawAngle;
const float yawDeg = ((values.value("yaw", 0.0f)/M_PI)*180.0f)+180.f;
//qDebug() << "YAW: " << yawDeg;
yawAngle.sprintf("%03d", (int)yawDeg);
paintText(yawAngle, defaultColor, 3.5f, -3.7f, compassY+ 0.9f, &painter);
// CHANGE RATE STRIPS
drawChangeRateStrip(-51.0f, -50.0f, 15.0f, -1.0f, 1.0f, valuesDot.value("z", 0.0f), &painter);
// CHANGE RATE STRIPS
drawChangeRateStrip(49.0f, -50.0f, 15.0f, -1.0f, 1.0f, valuesDot.value("x", 0.0f), &painter);
// GAUGES
// Left altitude gauge
drawChangeIndicatorGauge(-vGaugeSpacing, -15.0f, 10.0f, 2.0f, -values.value("z", 0.0f), defaultColor, &painter, false);