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 Implementation of Horizontal Situation Indicator class
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QFile>
#include <QStringList>
#include <QGraphicsScene>
#include <QHBoxLayout>
#include <QDoubleSpinBox>
#include "UASManager.h"
#include "HSIDisplay.h"
#include "UASWaypointManager.h"
#include "MAV2DIcon.h"
HSIDisplay::HSIDisplay(QWidget *parent) :
HDDisplay(NULL, "HSI", parent),
gpsSatellites(),
satellitesUsed(0),
attXSet(0.0f),
attYSet(0.0f),
attYawSet(0.0f),
altitudeSet(1.0f),
posXSet(0.0f),
posYSet(0.0f),
posZSet(0.0f),
attXSaturation(0.2f),
attYSaturation(0.2f),
attYawSaturation(0.5f),
posXSaturation(0.05f),
posYSaturation(0.05f),
altitudeSaturation(1.0f),
lat(0.0f),
lon(0.0f),
alt(0.0f),
globalAvailable(0),
x(0.0f),
y(0.0f),
z(0.0f),
vx(0.0f),
vy(0.0f),
vz(0.0f),
speed(0.0f),
localAvailable(0),
roll(0.0f),
pitch(0.0f),
yaw(0.0f),
bodyXSetCoordinate(0.0f),
bodyYSetCoordinate(0.0f),
bodyZSetCoordinate(0.0f),
bodyYawSet(0.0f),
uiXSetCoordinate(0.0f),
uiYSetCoordinate(0.0f),
uiYawSet(0.0f),
metricWidth(4.0),
positionLock(false),
attControlEnabled(false),
xyControlEnabled(false),
zControlEnabled(false),
yawControlEnabled(false),
positionFix(0),
gpsFix(0),
visionFix(0),
laserFix(0),
mavInitialized(false),
bottomMargin(10.0f),
dragStarted(false),
topMargin(12.0f),
leftDragStarted(false),
Lorenz Meier
committed
actionPending(false),
userSetPointSet(false),
userXYSetPointSet(false)
refreshTimer->setInterval(updateInterval);
this->setAutoFillBackground(true);
QPalette pal = palette();
pal.setColor(backgroundRole(), QGC::colorBlack);
setPalette(pal);
vwidth = 80.0f;
vheight = 80.0f;
yCenterPos = vheight/2.0f + topMargin - bottomMargin;
uas = NULL;
resetMAVState();
// Do first update
setMetricWidth(metricWidth);
// Set tooltip
setToolTip(tr("View from top in body frame. Scroll with mouse wheel to change the horizontal field of view of the widget."));
setStatusTip(tr("View from top in body frame. Scroll with mouse wheel to change the horizontal field of view of the widget."));
connect(&statusClearTimer, SIGNAL(timeout()), this, SLOT(clearStatusMessage()));
statusClearTimer.start(3000);
setFocusPolicy(Qt::StrongFocus);
HSIDisplay::~HSIDisplay()
{
}
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
void HSIDisplay::resetMAVState()
{
mavInitialized = false;
attControlKnown = false;
attControlEnabled = false;
xyControlKnown = false;
xyControlEnabled = false;
zControlKnown = false;
zControlEnabled = false;
yawControlKnown = false;
yawControlEnabled = false;
// Draw position lock indicators
positionFixKnown = false;
positionFix = 0;
visionFixKnown = false;
visionFix = 0;
gpsFixKnown = false;
gpsFix = 0;
iruFixKnown = false;
iruFix = 0;
// Data
setPointKnown = false;
localAvailable = 0;
globalAvailable = 0;
// Setpoints
positionSetPointKnown = false;
setPointKnown = false;
void HSIDisplay::paintEvent(QPaintEvent * event)
{
Q_UNUSED(event);
//paintGL();
// static quint64 interval = 0;
// //qDebug() << "INTERVAL:" << MG::TIME::getGroundTimeNow() - interval << __FILE__ << __LINE__;
// interval = MG::TIME::getGroundTimeNow();
renderOverlay();
void HSIDisplay::renderOverlay()
if (!isVisible()) return;
#if (QGC_EVENTLOOP_DEBUG)
qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
// Center location of the HSI gauge items
//const float margin = 0.1f; // 10% margin of total width on each side
float baseRadius = (vheight - topMargin - bottomMargin) / 2.0f - bottomMargin / 2.0f;
// Draw instruments
// TESTING THIS SHOULD BE MOVED INTO A QGRAPHICSVIEW
// 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;
QPainter painter(viewport());
painter.setRenderHint(QPainter::Antialiasing, true);
painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
// Draw base instrument
// ----------------------
const QColor ringColor = QColor(200, 250, 200);
QPen pen;
pen.setColor(ringColor);
pen.setWidth(refLineWidthToPen(0.1f));
painter.setPen(pen);
for (int i = 0; i < ringCount; i++) {
float radius = (vwidth - (topMargin + bottomMargin)*0.3f) / (1.35f * i+1) / 2.0f - bottomMargin / 2.0f;
drawCircle(xCenterPos, yCenterPos, radius, 0.1f, ringColor, &painter);
paintText(tr("%1 m").arg(refToMetric(radius), 5, 'f', 1, ' '), QGC::colorCyan, 1.6f, vwidth/2-4, vheight/2+radius+2.2, &painter);
// Draw orientation labels
// Translate and rotate coordinate frame
painter.translate((xCenterPos)*scalingFactor, (yCenterPos)*scalingFactor);
const float yawDeg = ((yaw/M_PI)*180.0f);
int yawRotate = static_cast<int>(yawDeg) % 360;
painter.rotate(-yawRotate);
paintText(tr("N"), ringColor, 3.5f, - 1.0f, - baseRadius - 5.5f, &painter);
paintText(tr("S"), ringColor, 3.5f, - 1.0f, + baseRadius + 1.5f, &painter);
paintText(tr("E"), ringColor, 3.5f, + baseRadius + 3.0f, - 1.25f, &painter);
paintText(tr("W"), ringColor, 3.5f, - baseRadius - 5.5f, - 1.75f, &painter);
painter.rotate(+yawRotate);
painter.translate(-(xCenterPos)*scalingFactor, -(yCenterPos)*scalingFactor);
// Draw trail
// QPointF m(bodyXSetCoordinate, bodyYSetCoordinate);
// // Transform from body to world coordinates
// m = metricWorldToBody(m);
// // Scale from metric body to screen reference units
// QPointF s = metricBodyToRef(m);
// drawLine(s.x(), s.y(), xCenterPos, yCenterPos, 1.5f, uas->getColor(), &painter);
// QPolygonF p(3);
// p.replace(0, QPointF(xCenterPos, yCenterPos-4.0f));
// p.replace(1, QPointF(xCenterPos-4.0f, yCenterPos+3.5f));
// p.replace(2, QPointF(xCenterPos+4.0f, yCenterPos+3.5f));
// drawPolygon(p, &painter);
// Translate to center
painter.translate((xCenterPos)*scalingFactor, (yCenterPos)*scalingFactor);
QColor uasColor = uas->getColor();
MAV2DIcon::drawAirframePolygon(uas->getAirframe(), painter, static_cast<int>((vwidth/4.0f)*scalingFactor*1.1f), uasColor, 0.0f);
//MAV2DIcon::drawAirframePolygon(uas->getAirframe(), painter, static_cast<int>((vwidth/4.0f)*scalingFactor*1.1f), uasColor, 0.0f);
// Translate back
painter.translate(-(xCenterPos)*scalingFactor, -(yCenterPos)*scalingFactor);
}
// Draw satellites
drawGPS(painter);
// Draw state indicator
// Draw position
drawPositionDirection(xCenterPos, yCenterPos, baseRadius, positionColor, &painter);
// Draw attitude
QColor attitudeColor(200, 20, 20);
drawAttitudeDirection(xCenterPos, yCenterPos, baseRadius, attitudeColor, &painter);
// Draw position setpoints in body coordinates
float xSpDiff = uiXSetCoordinate - bodyXSetCoordinate;
float ySpDiff = uiYSetCoordinate - bodyYSetCoordinate;
float zSpDiff = uiZSetCoordinate - bodyZSetCoordinate;
float setPointDist = sqrt(xSpDiff*xSpDiff + ySpDiff*ySpDiff + zSpDiff*zSpDiff);
float angleDiff = uiYawSet - bodyYawSet;
float normAngleDiff = fabs(atan2(sin(angleDiff), cos(angleDiff)));
if (userSetPointSet && setPointDist > 0.08f || normAngleDiff > 0.05f || dragStarted)
drawSetpointXYZYaw(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet, spColor, painter);
// Labels on outer part and bottom
// Draw waypoints
drawWaypoints(painter);
// Draw setpoint over waypoints
if (positionSetPointKnown)
{
drawSetpointXYZYaw(bodyXSetCoordinate, bodyYSetCoordinate, bodyZSetCoordinate, bodyYawSet, uas->getColor(), painter);
// Draw travel direction line
QPointF m(bodyXSetCoordinate, bodyYSetCoordinate);
// Transform from body to world coordinates
m = metricWorldToBody(m);
// Scale from metric body to screen reference units
drawLine(s.x(), s.y(), xCenterPos, yCenterPos, 1.5f, uas->getColor(), &painter);
// Draw status flags
drawStatusFlag(2, 1, tr("ATT"), attControlEnabled, attControlKnown, painter);
drawStatusFlag(22, 1, tr("PXY"), xyControlEnabled, xyControlKnown, painter);
drawStatusFlag(44, 1, tr("PZ"), zControlEnabled, zControlKnown, painter);
drawStatusFlag(66, 1, tr("YAW"), yawControlEnabled, yawControlKnown, painter);
// Draw position lock indicators
drawPositionLock(2, 5, tr("POS"), positionFix, positionFixKnown, painter);
drawPositionLock(22, 5, tr("VIS"), visionFix, visionFixKnown, painter);
drawPositionLock(44, 5, tr("GPS"), gpsFix, gpsFixKnown, painter);
drawPositionLock(66, 5, tr("IRU"), iruFix, iruFixKnown, painter);
// Draw speed to top left
paintText(tr("SPEED"), QGC::colorCyan, 2.2f, 2, 11, &painter);
paintText(tr("%1 m/s").arg(speed, 5, 'f', 2, '0'), Qt::white, 2.2f, 12, 11, &painter);
// Draw crosstrack error to top right
float crossTrackError = 0;
paintText(tr("XTRACK"), QGC::colorCyan, 2.2f, 54, 11, &painter);
paintText(tr("%1 m").arg(crossTrackError, 5, 'f', 2, '0'), Qt::white, 2.2f, 67, 11, &painter);
// Draw position to bottom left
if (localAvailable > 0 && globalAvailable == 0) {
// Position
QString str;
str.sprintf("%05.2f %05.2f %05.2f m", x, y, z);
paintText(tr("POS"), QGC::colorCyan, 2.6f, 2, vheight- 4.0f, &painter);
paintText(str, Qt::white, 2.6f, 10, vheight - 4.0f, &painter);
// Position
QString str;
str.sprintf("lat: %05.2f lon: %06.2f alt: %06.2f", lat, lon, alt);
paintText(tr("GPS"), QGC::colorCyan, 2.6f, 2, vheight- 4.0f, &painter);
paintText(str, Qt::white, 2.6f, 10, vheight - 4.0f, &painter);
// Draw Safety
double x1, y1, z1, x2, y2, z2;
UASManager::instance()->getLocalNEDSafetyLimits(&x1, &y1, &z1, &x2, &y2, &z2);
// drawSafetyArea(QPointF(x1, y1), QPointF(x2, y2), QGC::colorYellow, painter);
// Draw status message
paintText(statusMessage, QGC::colorOrange, 2.4f, 8, 15, &painter);
void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, bool known, QPainter& painter)
paintText(label, QGC::colorCyan, 2.6f, x, y+0.8f, &painter);
QColor statusColor(250, 250, 250);
painter.setBrush(QGC::colorDarkYellow);
}
painter.setPen(Qt::NoPen);
float indicatorWidth = refToScreenX(7.0f);
float indicatorHeight = refToScreenY(4.0f);
painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), indicatorWidth, indicatorHeight));
paintText((status) ? tr("ON") : tr("OFF"), statusColor, 2.6f, x+7.9f, y+0.8f, &painter);
// Cross out instrument if state unknown
QPen pen(Qt::yellow);
pen.setWidth(2);
painter.setPen(pen);
// Top left to bottom right
QPointF p1, p2, p3, p4;
p1.setX(refToScreenX(x));
p1.setY(refToScreenX(y));
p2.setX(p1.x()+indicatorWidth+refToScreenX(7.3f));
p2.setY(p1.y()+indicatorHeight);
painter.drawLine(p1, p2);
// Bottom left to top right
p3.setX(refToScreenX(x));
p3.setY(refToScreenX(y)+indicatorHeight);
p4.setX(p1.x()+indicatorWidth+refToScreenX(7.3f));
p4.setY(p1.y());
painter.drawLine(p3, p4);
}
void HSIDisplay::drawPositionLock(float x, float y, QString label, int status, bool known, QPainter& painter)
paintText(label, QGC::colorCyan, 2.6f, x, y+0.8f, &painter);
QColor negStatusColor(200, 20, 20);
QColor intermediateStatusColor (Qt::yellow);
QColor posStatusColor(20, 200, 20);
QColor statusColor(250, 250, 250);
if (status == 3) {
painter.setBrush(posStatusColor);
} else if (status == 2) {
painter.setBrush(intermediateStatusColor.dark(150));
} else {
painter.setBrush(negStatusColor);
}
// Lock text
QString lockText;
switch (status) {
case 1:
lockText = tr("LOC");
break;
case 2:
lockText = tr("2D");
break;
case 3:
lockText = tr("3D");
break;
default:
lockText = tr("NO");
break;
}
float indicatorWidth = refToScreenX(7.0f);
float indicatorHeight = refToScreenY(4.0f);
painter.setPen(Qt::NoPen);
painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), refToScreenX(7.0f), refToScreenY(4.0f)));
paintText(lockText, statusColor, 2.6f, x+7.9f, y+0.8f, &painter);
// Cross out instrument if state unknown
if (!known) {
QPen pen(Qt::yellow);
pen.setWidth(2);
painter.setPen(pen);
// Top left to bottom right
QPointF p1, p2, p3, p4;
p1.setX(refToScreenX(x));
p1.setY(refToScreenX(y));
p2.setX(p1.x()+indicatorWidth+refToScreenX(7.3f));
p2.setY(p1.y()+indicatorHeight);
painter.drawLine(p1, p2);
// Bottom left to top right
p3.setX(refToScreenX(x));
p3.setY(refToScreenX(y)+indicatorHeight);
p4.setX(p1.x()+indicatorWidth+refToScreenX(7.3f));
p4.setY(p1.y());
painter.drawLine(p3, p4);
}
void HSIDisplay::updatePositionLock(UASInterface* uas, bool lock)
{
void HSIDisplay::updateAttitudeControllerEnabled(bool enabled)
void HSIDisplay::updatePositionXYControllerEnabled(bool enabled)
void HSIDisplay::updatePositionZControllerEnabled(bool enabled)
void HSIDisplay::updateObjectPosition(unsigned int time, int id, int type, const QString& name, int quality, float bearing, float distance)
{
Q_UNUSED(quality);
Q_UNUSED(name);
Q_UNUSED(type);
Q_UNUSED(id);
Q_UNUSED(time);
// FIXME add multi-object support
QPainter painter(this);
QColor color(Qt::yellow);
float radius = vwidth / 20.0f;
QPen pen(color);
pen.setWidthF(refLineWidthToPen(0.4f));
pen.setColor(color);
painter.setPen(pen);
painter.setBrush(Qt::NoBrush);
QPointF in(cos(bearing)-sin(bearing)*distance, sin(bearing)+cos(bearing)*distance);
// Scale from metric to screen reference coordinates
QPointF p = metricBodyToRef(in);
drawCircle(p.x(), p.y(), radius, 0.4f, color, &painter);
}
QPointF HSIDisplay::metricWorldToBody(QPointF world)
{
// First translate to body-centered coordinates
// Rotate around -yaw
QPointF result(cos(angle) * (x - world.x()) - sin(angle) * (y - world.y()), sin(angle) * (x - world.x()) + cos(angle) * (y - world.y()));
return result;
}
QPointF HSIDisplay::metricBodyToWorld(QPointF body)
{
// First rotate into world coordinates
// then translate to world position
QPointF result((cos(-yaw) * body.x()) + (sin(-yaw) * body.y()) + x, (-sin(-yaw) * body.x()) + (cos(-yaw) * body.y()) + y);
QPointF HSIDisplay::screenToMetricBody(QPointF ref)
{
return QPointF(-((screenToRefY(ref.y()) - yCenterPos)/ vwidth) * metricWidth, ((screenToRefX(ref.x()) - xCenterPos) / vwidth) * metricWidth);
}
QPointF HSIDisplay::refToMetricBody(QPointF &ref)
{
return QPointF(-((ref.y() - yCenterPos)/ vwidth) * metricWidth - x, ((ref.x() - xCenterPos) / vwidth) * metricWidth - y);
}
/**
* @see refToScreenX()
*/
QPointF HSIDisplay::metricBodyToRef(QPointF &metric)
{
return QPointF(((metric.y())/ metricWidth) * vwidth + xCenterPos, ((-metric.x()) / metricWidth) * vwidth + yCenterPos);
}
double HSIDisplay::metricToRef(double metric)
{
return (metric / metricWidth) * vwidth;
}
double HSIDisplay::refToMetric(double ref)
{
return (ref/vwidth) * metricWidth;
}
QPointF HSIDisplay::metricBodyToScreen(QPointF metric)
{
QPointF ref = metricBodyToRef(metric);
ref.setX(refToScreenX(ref.x()));
ref.setY(refToScreenY(ref.y()));
return ref;
}
void HSIDisplay::mouseDoubleClickEvent(QMouseEvent * event)
{
if (event->type() == QMouseEvent::MouseButtonDblClick)
{
QPointF p = screenToMetricBody(event->posF());
setBodySetpointCoordinateXY(p.x(), p.y());
// qDebug() << "Double click at x: " << screenToRefX(event->x()) - xCenterPos << "y:" << screenToRefY(event->y()) - yCenterPos;
}
}
void HSIDisplay::mouseReleaseEvent(QMouseEvent * event)
{
if (mouseHasMoved)
if (event->type() == QMouseEvent::MouseButtonRelease && event->button() == Qt::RightButton)
{
if (dragStarted)
{
setBodySetpointCoordinateYaw(uiYawSet);
dragStarted = false;
}
}
if (event->type() == QMouseEvent::MouseButtonRelease && event->button() == Qt::LeftButton)
{
if (leftDragStarted)
{
setBodySetpointCoordinateZ(uiZSetCoordinate);
leftDragStarted = false;
mouseHasMoved = false;
}
void HSIDisplay::mousePressEvent(QMouseEvent * event)
{
if (event->type() == QMouseEvent::MouseButtonPress)
{
if (event->button() == Qt::RightButton)
{
startX = event->x();
// Start tracking mouse move
dragStarted = true;
}
else if (event->button() == Qt::LeftButton)
{
startY = event->y();
leftDragStarted = true;
mouseHasMoved = false;
void HSIDisplay::mouseMoveEvent(QMouseEvent * event)
{
if (event->type() == QMouseEvent::MouseMove)
{
if (dragStarted) uiYawSet -= 0.06f*(startX - event->x()) / this->frameSize().width();
if (leftDragStarted)
{
// uiZSetCoordinate -= 0.06f*(startY - event->y()) / this->frameSize().height();
// setBodySetpointCoordinateZ(uiZSetCoordinate);
if (leftDragStarted || dragStarted) mouseHasMoved = true;
if ((event->key() == Qt::Key_Enter || event->key() == Qt::Key_Return) && actionPending)
{
actionPending = false;
statusMessage = "SETPOINT SENT";
statusClearTimer.start();
sendBodySetPointCoordinates();
}
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
else if ((event->key() == Qt::Key_Down))
{
setBodySetpointCoordinateXY(-0.5, 0);
}
else if ((event->key() == Qt::Key_Left))
{
setBodySetpointCoordinateXY(0, -0.5);
}
else if ((event->key() == Qt::Key_Right))
{
setBodySetpointCoordinateXY(0, 0.5);
}
else if ((event->key() == Qt::Key_Plus))
{
setBodySetpointCoordinateZ(-0.2);
}
else if ((event->key() == Qt::Key_Minus))
{
setBodySetpointCoordinateZ(+0.2);
}
else if ((event->key() == Qt::Key_L))
{
setBodySetpointCoordinateYaw(-0.1);
}
else if ((event->key() == Qt::Key_R))
{
setBodySetpointCoordinateYaw(0.1);
}
HDDisplay::keyPressEvent(event);
void HSIDisplay::contextMenuEvent (QContextMenuEvent* event)
{
event->ignore();
}
void HSIDisplay::setMetricWidth(double width)
{
metricWidth = width;
emit metricWidthChanged(metricWidth);
}
}
/**
*
* @param uas the UAS/MAV to monitor/display with the HUD
*/
void HSIDisplay::setActiveUAS(UASInterface* uas)
{
if (this->uas != NULL) {
disconnect(this->uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
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(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64)));
disconnect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float)));
disconnect(this->uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
disconnect(this->uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool)));
disconnect(this->uas, SIGNAL(positionXYControlEnabled(bool)), this, SLOT(updatePositionXYControllerEnabled(bool)));
disconnect(this->uas, SIGNAL(positionZControlEnabled(bool)), this, SLOT(updatePositionZControllerEnabled(bool)));
disconnect(this->uas, SIGNAL(positionYawControlEnabled(bool)), this, SLOT(updatePositionYawControllerEnabled(bool)));
disconnect(this->uas, SIGNAL(localizationChanged(UASInterface*,int)), this, SLOT(updateLocalization(UASInterface*,int)));
disconnect(this->uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), this, SLOT(updateVisionLocalization(UASInterface*,int)));
disconnect(this->uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)), this, SLOT(updateGpsLocalization(UASInterface*,int)));
disconnect(this->uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int)));
disconnect(this->uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
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(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeSetpoints(UASInterface*,double,double,double,double,quint64)));
connect(uas, SIGNAL(positionSetPointsChanged(int,float,float,float,float,quint64)), this, SLOT(updatePositionSetpoints(int,float,float,float,float,quint64)));
connect(uas, SIGNAL(userPositionSetPointsChanged(int,float,float,float,float)), this, SLOT(updateUserPositionSetpoints(int,float,float,float,float)));
connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool)));
connect(uas, SIGNAL(positionXYControlEnabled(bool)), this, SLOT(updatePositionXYControllerEnabled(bool)));
connect(uas, SIGNAL(positionZControlEnabled(bool)), this, SLOT(updatePositionZControllerEnabled(bool)));
connect(uas, SIGNAL(positionYawControlEnabled(bool)), this, SLOT(updatePositionYawControllerEnabled(bool)));
connect(uas, SIGNAL(localizationChanged(UASInterface*,int)), this, SLOT(updateLocalization(UASInterface*,int)));
connect(uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), this, SLOT(updateVisionLocalization(UASInterface*,int)));
connect(uas, SIGNAL(gpsLocalizationChanged(UASInterface*,int)), this, SLOT(updateGpsLocalization(UASInterface*,int)));
connect(uas, SIGNAL(irUltraSoundLocalizationChanged(UASInterface*,int)), this, SLOT(updateInfraredUltrasoundLocalization(UASInterface*,int)));
connect(uas, SIGNAL(objectDetected(uint,int,int,QString,int,float,float)), this, SLOT(updateObjectPosition(uint,int,int,QString,int,float,float)));
void HSIDisplay::updateSpeed(UASInterface* uas, double vx, double vy, double vz, quint64 time)
{
Q_UNUSED(uas);
Q_UNUSED(time);
this->vx = vx;
this->vy = vy;
this->vz = vz;
this->speed = sqrt(pow(vx, 2.0) + pow(vy, 2.0) + pow(vz, 2.0));
}
void HSIDisplay::setBodySetpointCoordinateXY(double x, double y)
{
userXYSetPointSet = true;
// Set coordinates and send them out to MAV
QPointF sp(x, y);
sp = metricBodyToWorld(sp);
uiXSetCoordinate = sp.x();
uiYSetCoordinate = sp.y();
qDebug() << "Attempting to set new setpoint at x: " << x << "metric y:" << y;
if (uas && mavInitialized)
{
//sendBodySetPointCoordinates();
statusMessage = "POSITION SET, PRESS <ENTER> TO SEND";
actionPending = true;
statusClearTimer.start();
}
void HSIDisplay::setBodySetpointCoordinateZ(double z)
{
// Set coordinates and send them out to MAV
uiZSetCoordinate = z;
statusMessage = "Z SET, PRESS <ENTER> TO SEND";
actionPending = true;
statusClearTimer.start();
//sendBodySetPointCoordinates();
}
void HSIDisplay::setBodySetpointCoordinateYaw(double yaw)
{
if (!userXYSetPointSet && setPointKnown)
{
uiXSetCoordinate = bodyXSetCoordinate;
uiYSetCoordinate = bodyYSetCoordinate;
}
else if (!userXYSetPointSet && mavInitialized)
{
QPointF coord = metricBodyToWorld(QPointF(0.0, 0.0));
uiXSetCoordinate = coord.x();
uiYSetCoordinate = coord.y();
}
userSetPointSet = true;
// Set coordinates and send them out to MAV
uiYawSet = atan2(sin(yaw), cos(yaw));
statusMessage = "YAW SET, PRESS <ENTER> TO SEND";
statusClearTimer.start();
actionPending = true;
//sendBodySetPointCoordinates();
}
void HSIDisplay::sendBodySetPointCoordinates()
{
// Send the coordinates to the MAV
if (uas && mavInitialized)
{
double dx = uiXSetCoordinate - uas->getLocalX();
double dy = uiYSetCoordinate - uas->getLocalY();
double dz = uiZSetCoordinate - uas->getLocalZ();
bool valid = (sqrt(dx*dx + dy*dy + dz*dz) < 1.0);//UASManager::instance()->isInLocalNEDSafetyLimits(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate);
if (valid)
{
uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet);
}
else
{
setStatusMessage("REJECTED NEW SETPOINT: OUT OF BOUNDS");
}
}
void HSIDisplay::updateAttitudeSetpoints(UASInterface* uas, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec)
Q_UNUSED(uas);
Q_UNUSED(usec);
attXSet = pitchDesired;
attYSet = rollDesired;
attYawSet = yawDesired;
altitudeSet = thrustDesired;
void HSIDisplay::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 time)
{
Q_UNUSED(uas);
Q_UNUSED(time);
this->roll = roll;
this->pitch = pitch;
this->yaw = yaw;
}
void HSIDisplay::updateUserPositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired)
{
uiXSetCoordinate = xDesired;
uiYSetCoordinate = yDesired;
uiZSetCoordinate = zDesired;
uiYawSet = yawDesired;
userXYSetPointSet = true;
userSetPointSet = true;
}
void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec)
bodyXSetCoordinate = xDesired;
bodyYSetCoordinate = yDesired;
bodyZSetCoordinate = zDesired;
bodyYawSet = yawDesired;
positionSetPointKnown = true;
if (!userSetPointSet && !dragStarted)
{
uiXSetCoordinate = bodyXSetCoordinate;
uiYSetCoordinate = bodyYSetCoordinate;
uiYawSet= bodyYawSet;
}
}
void HSIDisplay::updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec)
{
this->x = x;
this->y = y;
this->z = z;
localAvailable = usec;
}
void HSIDisplay::updateGlobalPosition(UASInterface*, double lat, double lon, double alt, quint64 usec)
{
this->lat = lat;
this->lon = lon;
this->alt = alt;
globalAvailable = usec;
void HSIDisplay::updateSatellite(int uasid, int satid, float elevation, float azimuth, float snr, bool used)
if (gpsSatellites.contains(satid)) {
gpsSatellites.value(satid)->update(satid, elevation, azimuth, snr, used);
gpsSatellites.insert(satid, new GPSSatellite(satid, elevation, azimuth, snr, used));
void HSIDisplay::updatePositionYawControllerEnabled(bool enabled)
{
yawControlEnabled = enabled;
}
/**
* @param fix 0: lost, 1: 2D local position hold, 2: 2D localization, 3: 3D localization
*/
void HSIDisplay::updateLocalization(UASInterface* uas, int fix)
{
Q_UNUSED(uas);
positionFix = fix;
//qDebug() << "LOCALIZATION FIX CALLED";
}
/**
* @param fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D localization, 3: 3D localization
*/
void HSIDisplay::updateGpsLocalization(UASInterface* uas, int fix)
{
Q_UNUSED(uas);
gpsFix = fix;
}
/**
* @param fix 0: lost, 1: 2D local position hold, 2: 2D localization, 3: 3D localization
*/
void HSIDisplay::updateVisionLocalization(UASInterface* uas, int fix)
{
Q_UNUSED(uas);
visionFix = fix;
//qDebug() << "VISION FIX GOT CALLED";
/**
* @param fix 0: lost, 1-N: Localized with N ultrasound or infrared sensors
*/
void HSIDisplay::updateInfraredUltrasoundLocalization(UASInterface* uas, int fix)
{
Q_UNUSED(uas);
iruFix = fix;
} else if (snr >= 30 && snr < 35) {
} else if (snr >= 35 && snr < 40) {
void HSIDisplay::drawSetpointXYZYaw(float x, float y, float z, float yaw, const QColor &color, QPainter &painter)
float radius = vwidth / 18.0f;
QPen pen(color);
pen.setWidthF(refLineWidthToPen(0.4f));
pen.setColor(color);
painter.setPen(pen);
painter.setBrush(Qt::NoBrush);
QPointF in(x, y);
// Transform from body to world coordinates
in = metricWorldToBody(in);
// Scale from metric to screen reference coordinates
QPointF p = metricBodyToRef(in);
QPolygonF poly(4);
// Top point
poly.replace(0, QPointF(p.x()-radius, p.y()-radius));
// Right point
poly.replace(1, QPointF(p.x()+radius, p.y()-radius));
// Bottom point
poly.replace(2, QPointF(p.x()+radius, p.y()+radius));
poly.replace(3, QPointF(p.x()-radius, p.y()+radius));
// Label
paintText(QString("z: %1 m").arg(z), color, 1.2f, p.x()-radius, p.y()-radius-2.0f, &painter);
drawPolygon(poly, &painter);
drawLine(p.x(), p.y(), p.x()+sin(-yaw + uas->getYaw() + M_PI) * radius, p.y()+cos(-yaw + uas->getYaw() + M_PI) * radius, refLineWidthToPen(0.4f), color, &painter);