Commit e6d7dec4 authored by lm's avatar lm

Added map view, fixed audio output

parent 77ec7b8e
...@@ -197,6 +197,7 @@ bool GAudioOutput::startEmergency() ...@@ -197,6 +197,7 @@ bool GAudioOutput::startEmergency()
// Beep immediately and then start timer // Beep immediately and then start timer
beep(); beep();
emergencyTimer->start(1500); emergencyTimer->start(1500);
QTimer::singleShot(5000, this, SLOT(stopEmergency()));
} }
return true; return true;
} }
......
...@@ -55,8 +55,8 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -55,8 +55,8 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, str+".x", vect.x, MG::TIME::getGroundTimeNow()); emit valueChanged(uasId, str+".x", vect.x, MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, str+".y", vect.y, MG::TIME::getGroundTimeNow()); emit valueChanged(uasId, str+".y", vect.y, MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, str+".z", vect.z, MG::TIME::getGroundTimeNow()); emit valueChanged(uasId, str+".z", vect.z, MG::TIME::getGroundTimeNow());
break;
} }
break;
default: default:
// Do nothing // Do nothing
break; break;
......
...@@ -289,7 +289,7 @@ signals: ...@@ -289,7 +289,7 @@ signals:
void attitudeChanged(UASInterface*, double roll, double pitch, double yaw, quint64 usec); void attitudeChanged(UASInterface*, double roll, double pitch, double yaw, quint64 usec);
void attitudeThrustSetPointChanged(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec); void attitudeThrustSetPointChanged(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec);
void localPositionChanged(UASInterface*, double x, double y, double z, quint64 usec); void localPositionChanged(UASInterface*, double x, double y, double z, quint64 usec);
void globalPositionChanged(UASInterface*, double lon, double lat, double alt, quint64 usec); void globalPositionChanged(UASInterface*, double lat, double lon, double alt, quint64 usec);
void speedChanged(UASInterface*, double x, double y, double z, quint64 usec); void speedChanged(UASInterface*, double x, double y, double z, quint64 usec);
void imageStarted(int imgid, int width, int height, int depth, int channels); void imageStarted(int imgid, int width, int height, int depth, int channels);
void imageDataReceived(int imgid, const unsigned char* imageData, int length, int startIndex); void imageDataReceived(int imgid, const unsigned char* imageData, int length, int startIndex);
......
...@@ -31,6 +31,8 @@ This file is part of the PIXHAWK project ...@@ -31,6 +31,8 @@ This file is part of the PIXHAWK project
#include "MapWidget.h" #include "MapWidget.h"
#include "ui_MapWidget.h" #include "ui_MapWidget.h"
#include "UASInterface.h"
#include "UASManager.h"
MapWidget::MapWidget(QWidget *parent) : MapWidget::MapWidget(QWidget *parent) :
QWidget(parent), QWidget(parent),
...@@ -54,7 +56,7 @@ MapWidget::MapWidget(QWidget *parent) : ...@@ -54,7 +56,7 @@ MapWidget::MapWidget(QWidget *parent) :
//GoogleSatMapAdapter* gSatAdapter = new GoogleSatMapAdapter(); //GoogleSatMapAdapter* gSatAdapter = new GoogleSatMapAdapter();
// create a layer with the mapadapter and type MapLayer // create a layer with the mapadapter and type MapLayer
Layer* osmLayer = new Layer("Custom Layer", osmAdapter, Layer::MapLayer); osmLayer = new Layer("Custom Layer", osmAdapter, Layer::MapLayer);
//Layer* gSatLayer = new Layer("Custom Layer", gSatAdapter, Layer::MapLayer); //Layer* gSatLayer = new Layer("Custom Layer", gSatAdapter, Layer::MapLayer);
// add Layer to the MapControl // add Layer to the MapControl
...@@ -97,20 +99,67 @@ MapWidget::MapWidget(QWidget *parent) : ...@@ -97,20 +99,67 @@ MapWidget::MapWidget(QWidget *parent) :
//gm->start(); //gm->start();
mc->setZoom(3); mc->setZoom(3);
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)));
} }
MapWidget::~MapWidget() MapWidget::~MapWidget()
{ {
delete m_ui; delete m_ui;
} }
/**
*
* @param uas the UAS/MAV to monitor/display with the HUD
*/
void MapWidget::addUAS(UASInterface* uas)
{
mav = uas;
}
void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
{
Q_UNUSED(usec);
// create a LineString
QList<Point*> points;
// Points with a circle
// A QPen can be used to customize the
QPen* pointpen = new QPen(QColor(0,255,0));
pointpen->setWidth(3);
points.append(new CirclePoint(lat, lon, alt, uas->getUASName(), Point::Middle, pointpen));
// points.append(new CirclePoint(8.275145, 50.016992, 15, "Wiesbaden-Mainz-Kastel, Johannes-Goßner-Straße", Point::Middle, pointpen));
// points.append(new CirclePoint(8.270476, 50.021426, 15, "Wiesbaden-Mainz-Kastel, Ruthof", Point::Middle, pointpen));
// // "Blind" Points
// points.append(new Point(8.266445, 50.025913, "Wiesbaden-Mainz-Kastel, Mudra Kaserne"));
// points.append(new Point(8.260378, 50.030345, "Wiesbaden-Mainz-Amoneburg, Dyckerhoffstraße"));
// A QPen also can use transparency
QPen* linepen = new QPen(QColor(0, 0, 255, 100));
linepen->setWidth(5);
// Add the Points and the QPen to a LineString
LineString* ls = new LineString(points, "Path", linepen);
// Add the LineString to the layer
osmLayer->addGeometry(ls);
// Connect click events of the layer to this object
//connect(osmLayer, SIGNAL(geometryClicked(Geometry*, QPoint)),
// this, SLOT(geometryClicked(Geometry*, QPoint)));
// Sets the view to the interesting area
//QList<QPointF> view;
//view.append(QPointF(8.24764, 50.0319));
//view.append(QPointF(8.28412, 49.9998));
// mc->setView(view);
updatePosition(0, lat, lon);
}
void MapWidget::updatePosition(float time, QPointF coordinate) void MapWidget::updatePosition(float time, double lat, double lon)
{ {
gpsposition->setText(QString::number(time) + " / " + QString::number(coordinate.x()) + " / " + QString::number(coordinate.y())); gpsposition->setText(QString::number(time) + " / " + QString::number(lat) + " / " + QString::number(lon));
if (followgps->isChecked()) if (followgps->isChecked())
{ {
mc->setView(coordinate); mc->setView(QPointF(lat, lon));
} }
} }
......
...@@ -34,6 +34,7 @@ This file is part of the PIXHAWK project ...@@ -34,6 +34,7 @@ This file is part of the PIXHAWK project
#include <QtGui/QWidget> #include <QtGui/QWidget>
#include "qmapcontrol.h" #include "qmapcontrol.h"
#include "UASInterface.h"
namespace Ui { namespace Ui {
class MapWidget; class MapWidget;
...@@ -48,7 +49,9 @@ public: ...@@ -48,7 +49,9 @@ public:
~MapWidget(); ~MapWidget();
public slots: public slots:
void updatePosition(float time, QPointF coordinate); void addUAS(UASInterface* uas);
void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
void updatePosition(float time, double lat, double lon);
protected: protected:
void changeEvent(QEvent* e); void changeEvent(QEvent* e);
...@@ -68,6 +71,8 @@ protected: ...@@ -68,6 +71,8 @@ protected:
Layer* osmLayer; Layer* osmLayer;
Layer* gSatLayer; Layer* gSatLayer;
UASInterface* mav;
private: private:
Ui::MapWidget *m_ui; Ui::MapWidget *m_ui;
}; };
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment