Newer
Older
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009, 2010 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK 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.
PIXHAWK 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 PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Head Up Display (HUD)
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QDebug>
#include <cmath>
#include "UASManager.h"
#include "HUD.h"
#include "MG.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),
69
70
71
72
73
74
75
76
77
78
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
uas(NULL),
values(QMap<QString, float>()),
valuesDot(QMap<QString, float>()),
valuesMean(QMap<QString, float>()),
valuesCount(QMap<QString, int>()),
lastUpdate(QMap<QString, quint64>()),
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("")
{
// Set auto fill to false
setAutoFillBackground(false);
// 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 = MG::DIR::getIconDirectory() + "hud-template.png";
//qDebug() << __FILE__ << __LINE__ << "template image:" << imagePath;
//fill = QImage(imagePath);
glImage = QGLWidget::convertToGLFormat(fill);
// Refresh timer
refreshTimer->setInterval(40); // 25 Hz
connect(refreshTimer, SIGNAL(timeout()), this, SLOT(update()));
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
// Resize to correct size and fill with image
resize(fill.size());
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", (int)(10*scalingFactor*1.2f+0.5f));
if (font.family() != fontFamilyName) qDebug() << "ERROR! Font not loaded: " << fontFamilyName;
// Connect with UAS
UASManager* manager = UASManager::instance();
connect(manager, SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
}
HUD::~HUD()
{
}
void HUD::start()
{
refreshTimer->start();
}
void HUD::stop()
{
refreshTimer->stop();
}
void HUD::updateValue(UASInterface* uas, QString name, double value, quint64 msec)
{
// UAS is not needed
Q_UNUSED(uas);
// Update mean
const float oldMean = valuesMean.value(name, 0.0f);
const int meanCount = valuesCount.value(name, 0);
double mean = (oldMean * meanCount + value) / (meanCount + 1);
if (isnan(mean) || isinf(mean)) mean = 0.0;
valuesMean.insert(name, mean);
valuesCount.insert(name, meanCount + 1);
// Two-value sliding average
double dot = (valuesDot.value(name) + (value - values.value(name, 0.0f)) / ((msec - lastUpdate.value(name, 0))/1000.0f))/2.0f;
if (isnan(dot) || isinf(dot))
{
dot = 0.0;
}
//qDebug() << __FILE__ << __LINE__ << "VALUE:" << value << "MEAN:" << mean << "DOT:" << dot << "COUNT:" << meanCount;
}
/**
*
* @param uas the UAS/MAV to monitor/display with the HUD
*/
void HUD::setActiveUAS(UASInterface* uas)
{
qDebug() << "ATTEMPTING TO SET UAS";
if (this->uas != NULL && this->uas != uas)
{
// Disconnect any previously connected active MAV
disconnect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*, double, double, double, quint64)));
disconnect(uas, SIGNAL(batteryChanged(UASInterface*, double, double, int)), this, SLOT(updateBattery(UASInterface*, double, double, int)));
disconnect(uas, SIGNAL(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*)));
disconnect(uas, SIGNAL(thrustChanged(UASInterface*, double)), this, SLOT(updateThrust(UASInterface*, double)));
disconnect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
disconnect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
disconnect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
disconnect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString)));
disconnect(uas, SIGNAL(modeChanged(UASInterface*,QString,QString)), this, SLOT(updateMode(UASInterface*,QString)));
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
disconnect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateLoad(UASInterface*, double)));
disconnect(uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeThrustSetPoint(UASInterface*,double,double,double,double,quint64)));
disconnect(uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
}
// Now connect the new UAS
//if (this->uas != uas)
// {
qDebug() << "UAS SET!" << "ID:" << uas->getUASID();
// 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(heartbeat(UASInterface*)), this, SLOT(receiveHeartbeat(UASInterface*)));
//connect(uas, SIGNAL(thrustChanged(UASInterface*, double)), this, SLOT(updateThrust(UASInterface*, double)));
//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)));
//connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
//connect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString,QString)));
//connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateLoad(UASInterface*, double)));
//connect(uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeThrustSetPoint(UASInterface*,double,double,double,double,quint64)));
//connect(uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
//}
}
void HUD::updateAttitudeThrustSetPoint(UASInterface*, 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)
{
//qDebug() << __FILE__ << __LINE__ << "ROLL" << roll;
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
updateValue(uas, "roll", roll, timestamp);
updateValue(uas, "pitch", pitch, timestamp);
updateValue(uas, "yaw", yaw, timestamp);
}
void HUD::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)
{
updateValue(uas, "voltage", voltage, MG::TIME::getGroundTimeNow());
updateValue(uas, "time remaining", seconds, MG::TIME::getGroundTimeNow());
updateValue(uas, "charge level", percent, MG::TIME::getGroundTimeNow());
if (percent < 20.0f)
{
fuelColor = warningColor;
}
else if (percent < 10.0f)
{
fuelColor = criticalColor;
}
else
{
fuelColor = infoColor;
}
}
void HUD::receiveHeartbeat(UASInterface*)
{
}
void HUD::updateThrust(UASInterface*, double thrust)
{
updateValue(uas, "thrust", thrust, MG::TIME::getGroundTimeNow());
}
void HUD::updateLocalPosition(UASInterface* uas,double x,double y,double z,quint64 timestamp)
{
updateValue(uas, "x", x, timestamp);
updateValue(uas, "y", y, timestamp);
updateValue(uas, "z", z, timestamp);
}
void HUD::updateGlobalPosition(UASInterface*,double lat, double lon, double altitude, quint64 timestamp)
{
updateValue(uas, "lat", lat, timestamp);
updateValue(uas, "lon", lon, timestamp);
updateValue(uas, "altitude", altitude, timestamp);
}
void HUD::updateSpeed(UASInterface* uas,double x,double y,double z,quint64 timestamp)
{
updateValue(uas, "xSpeed", x, timestamp);
updateValue(uas, "ySpeed", y, timestamp);
updateValue(uas, "zSpeed", z, timestamp);
}
/**
* 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(UASInterface* uas,QString mode)
{
// Only one UAS is connected at a time
Q_UNUSED(uas);
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
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
}
void HUD::updateLoad(UASInterface* uas, double load)
{
updateValue(uas, "load", load, MG::TIME::getGroundTimeNow());
}
/**
* @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);
// Rotate based on the bank
glRotatef((roll/M_PI)*180.0f, 0, 0, 1);
// 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);
// 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");
font.setPixelSize((int)(fontSize*scalingFactor*1.26f));
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
if(antialiasing)
{
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);
}
else
{
glDisable(GL_BLEND);
glDisable(GL_POINT_SMOOTH);
glDisable(GL_LINE_SMOOTH);
477
478
479
480
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
}
}
/**
* @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()
{
}
// Event is not needed
Q_UNUSED(event);
// Read out most important values to limit hash table lookups
static float roll = 0.0;
static float pitch = 0.0;
static float yaw = 0.0;
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);
// 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
glMatrixMode(GL_MODELVIEW);
glPushMatrix();
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
// Blue / Brown background
if (noCamera) paintCenterBackground(roll, pitch, yaw);
glMatrixMode(GL_MODELVIEW);
glPopMatrix();
QPainter painter;
painter.begin(this);
painter.setRenderHint(QPainter::Antialiasing, true);
//painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
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
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
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);
// 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);
// CENTER
// 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)));
// 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);
// Right speed gauge
drawChangeIndicatorGauge(vGaugeSpacing, -15.0f, 10.0f, 5.0f, values.value("xSpeed", 0.0f), defaultColor, &painter, false);
// MOVING PARTS
// Translate for yaw
const float maxYawTrans = 60.0f;
float yawDiff = valuesDot.value("yaw", 0.0f);
if (isinf(yawDiff)) yawDiff = 0.0f;
if (yawDiff > M_PI) yawDiff = yawDiff - M_PI;
if (yawDiff < -M_PI) yawDiff = yawDiff + M_PI;
yawInt += yawDiff;
if (yawInt > M_PI) yawInt = M_PI;
if (yawInt < -M_PI) yawInt = -M_PI;
float yawTrans = yawInt * (double)maxYawTrans;
yawInt *= 0.6f;
//qDebug() << "yaw translation" << yawTrans << "integral" << yawInt << "difference" << yawDiff << "yaw" << yaw << "asin(yawInt)" << asinYaw;
painter.translate(0, (pitch/M_PI)* -180.0f * refToScreenY(1.8));
painter.translate(refToScreenX(yawTrans), 0);
// Rotate view and draw all roll-dependent indicators
painter.rotate((roll/M_PI)* -180.0f);
//qDebug() << "ROLL" << roll << "PITCH" << pitch << "YAW DIFF" << valuesDot.value("roll", 0.0f);
// PITCH
paintPitchLines((pitch/M_PI)*180.0f, &painter);
painter.end();
}
/*
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)));
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
// 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);
// Right speed gauge
drawChangeIndicatorGauge(vGaugeSpacing, -15.0f, 10.0f, 5.0f, values.value("xSpeed", 0.0f), defaultColor, &painter, false);
if (isinf(yawDiff)) yawDiff = 0.0f;
if (yawDiff > M_PI) yawDiff = yawDiff - M_PI;
yawInt += yawDiff;
if (yawInt > M_PI) yawInt = M_PI;
if (yawInt < -M_PI) yawInt = -M_PI;
float yawTrans = yawInt * (double)maxYawTrans;
yawInt *= 0.6f;
//qDebug() << "yaw translation" << yawTrans << "integral" << yawInt << "difference" << yawDiff << "yaw" << yaw << "asin(yawInt)" << asinYaw;
// Rotate view and draw all roll-dependent indicators
painter.rotate((roll/M_PI)* -180.0f);
//qDebug() << "ROLL" << roll << "PITCH" << pitch << "YAW DIFF" << valuesDot.value("roll", 0.0f);
// PITCH
paintPitchLines((pitch/M_PI)*180.0f, &painter);
painter.end();
glFlush();
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
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
/**
* @param pitch pitch angle in degrees (-180 to 180)
*/
void HUD::paintPitchLines(float pitch, QPainter* painter)
{
QString label;
const float yDeg = vPitchPerDeg;
const float lineDistance = 5.0f; ///< One pitch line every 10 degrees
const float posIncrement = yDeg * lineDistance;
float posY = posIncrement;
const float posLimit = sqrt(pow(vwidth, 2.0f) + pow(vheight, 2.0f));
const float offsetAbs = pitch * yDeg;
float offset = pitch;
if (offset < 0) offset = -offset;
int offsetCount = 0;
while (offset > lineDistance)
{
offset -= lineDistance;
offsetCount++;
}
int iPos = (int)(0.5f + lineDistance); ///< The first line
int iNeg = (int)(-0.5f - lineDistance); ///< The first line
offset *= yDeg;
painter->setPen(defaultColor);
posY = -offsetAbs + posIncrement; //+ 100;// + lineDistance;
while (posY < posLimit)
{
paintPitchLinePos(label.sprintf("%3d", iPos), 0.0f, -posY, painter);
posY += posIncrement;
iPos += (int)lineDistance;
}
// HORIZON
//
// ------------ ------------
//
const float pitchWidth = 30.0f;
const float pitchGap = pitchWidth / 2.5f;
const QColor horizonColor = defaultColor;
const float diagonal = sqrt(pow(vwidth, 2.0f) + pow(vheight, 2.0f));
const float lineWidth = refLineWidthToPen(0.5f);
// Left horizon
drawLine(0.0f-diagonal, offsetAbs, 0.0f-pitchGap/2.0f, offsetAbs, lineWidth, horizonColor, painter);
// Right horizon
drawLine(0.0f+pitchGap/2.0f, offsetAbs, 0.0f+diagonal, offsetAbs, lineWidth, horizonColor, painter);
label.clear();
posY = offsetAbs + posIncrement;
while (posY < posLimit)
{
paintPitchLineNeg(label.sprintf("%3d", iNeg), 0.0f, posY, painter);
posY += posIncrement;
iNeg -= (int)lineDistance;
}
}
void HUD::paintPitchLinePos(QString text, float refPosX, float refPosY, QPainter* painter)
{
//painter->setPen(QPen(QBrush, normalStrokeWidth));
const float pitchWidth = 30.0f;
const float pitchGap = pitchWidth / 2.5f;
const float pitchHeight = pitchWidth / 12.0f;
const float textSize = pitchHeight * 1.1f;
const float lineWidth = 0.5f;
// Positive pitch indicator:
//
// _______ _______
// |10 |
//
// Left vertical line
drawLine(refPosX-pitchWidth/2.0f, refPosY, refPosX-pitchWidth/2.0f, refPosY+pitchHeight, lineWidth, defaultColor, painter);
// Left horizontal line
drawLine(refPosX-pitchWidth/2.0f, refPosY, refPosX-pitchGap/2.0f, refPosY, lineWidth, defaultColor, painter);
// Text left
paintText(text, defaultColor, textSize, refPosX-pitchWidth/2.0 + 0.75f, refPosY + pitchHeight - 1.75f, painter);
// Right vertical line
drawLine(refPosX+pitchWidth/2.0f, refPosY, refPosX+pitchWidth/2.0f, refPosY+pitchHeight, lineWidth, defaultColor, painter);
// Right horizontal line
drawLine(refPosX+pitchWidth/2.0f, refPosY, refPosX+pitchGap/2.0f, refPosY, lineWidth, defaultColor, painter);