diff --git a/lib/QMapControl/src/layer.cpp b/lib/QMapControl/src/layer.cpp index fa88211..32f6358 100644 --- a/lib/QMapControl/src/layer.cpp +++ b/lib/QMapControl/src/layer.cpp @@ -97,6 +97,36 @@ namespace qmapcontrol geometries.clear(); } + Geometry* Layer::get_Geometry(int index) + { + if(geometrySelected) + { + return geometrySelected; + } + else + { + for(int i = 0; i <= geometries.size(); i++) + { + Geometry *geometry = geometries[i]; + if(geometry->name() == QString::number(index)) + { + return geometry; + } + } + +// foreach(Geometry *geometry, geometries) +// { + +// if(geometry->name() == QString::number(index)) +// { +// return geometry; +// } + +// } + } + + } + bool Layer::isVisible() const { return visible; @@ -323,3 +353,5 @@ namespace qmapcontrol mapAdapter = mapadapter; } } + + diff --git a/lib/QMapControl/src/layer.h b/lib/QMapControl/src/layer.h index 9d67791..46fd5b1 100644 --- a/lib/QMapControl/src/layer.h +++ b/lib/QMapControl/src/layer.h @@ -200,6 +200,12 @@ namespace qmapcontrol */ void setVisible(bool visible); + //! get geometry selected by index + /*! + * @param index of geometry selected + */ + Geometry* get_Geometry(int index); + }; } #endif diff --git a/lib/QMapControl/src/mapcontrol.cpp b/lib/QMapControl/src/mapcontrol.cpp index 7d53b7f..2f4c6d6 100644 --- a/lib/QMapControl/src/mapcontrol.cpp +++ b/lib/QMapControl/src/mapcontrol.cpp @@ -309,6 +309,7 @@ namespace qmapcontrol click.y()-screen_middle.y()+layermanager->getMapmiddle_px().y()); // image coordinate to world coordinate return layermanager->layer()->mapadapter()->displayToCoordinate(displayToImage); + } void MapControl::updateRequest(QRect rect) diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 380b3ea..1efdd1c 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -159,7 +159,6 @@ HEADERS += src/MG.h \ src/ui/map/Waypoint2DIcon.h \ src/ui/map/MAV2DIcon.h \ src/ui/QGCRemoteControlView.h \ - src/WaypointGlobal.h \ src/ui/WaypointGlobalView.h \ src/ui/map3D/Q3DWidget.h \ src/ui/map3D/CheetahModel.h \ @@ -233,8 +232,7 @@ SOURCES += src/main.cc \ src/ui/map/Waypoint2DIcon.cc \ src/ui/map/MAV2DIcon.cc \ src/ui/QGCRemoteControlView.cc \ - src/WaypointGlobal.cpp \ - src/ui/WaypointGlobalView.cpp \ + src/ui/WaypointGlobalView.cc \ src/ui/map3D/Q3DWidget.cc \ src/ui/map3D/CheetahModel.cc \ src/ui/map3D/CheetahGL.cc \ diff --git a/src/Waypoint.h b/src/Waypoint.h index d8baeba..8e8f400 100644 --- a/src/Waypoint.h +++ b/src/Waypoint.h @@ -81,6 +81,7 @@ public slots: void setOrbit(float orbit); void setHoldTime(int holdTime); + //for QDoubleSpin void setX(double x); void setY(double y); diff --git a/src/WaypointGlobal.cpp b/src/WaypointGlobal.cpp deleted file mode 100644 index fc5526f..0000000 --- a/src/WaypointGlobal.cpp +++ /dev/null @@ -1,10 +0,0 @@ -#include "WaypointGlobal.h" - -#include - -WaypointGlobal::WaypointGlobal(const QPointF coordinate): - Waypoint(id, x, y, z, yaw, autocontinue, current, orbit, holdTime) -{ - coordinateWP = coordinate; - -} diff --git a/src/WaypointGlobal.h b/src/WaypointGlobal.h deleted file mode 100644 index 4a3bc4e..0000000 --- a/src/WaypointGlobal.h +++ /dev/null @@ -1,29 +0,0 @@ -#ifndef WAYPOINTGLOBAL_H -#define WAYPOINTGLOBAL_H - -#include "Waypoint.h" -#include - -class WaypointGlobal: public Waypoint { - Q_OBJECT - -public: - WaypointGlobal(const QPointF coordinate); - - public slots: - -// void set_latitud(double latitud); -// void set_longitud(double longitud); -// double get_latitud(); -// double get_longitud(); - -private: - QPointF coordinateWP; - - - - - -}; - -#endif // WAYPOINTGLOBAL_H diff --git a/src/uas/SlugsMAV.cc b/src/uas/SlugsMAV.cc index 9a8c2da..bfadeda 100644 --- a/src/uas/SlugsMAV.cc +++ b/src/uas/SlugsMAV.cc @@ -53,7 +53,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) break; } -#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES +#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES_QGC case MAVLINK_MSG_ID_CPU_LOAD: { diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 3a6d7d5..bf01124 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -171,6 +171,9 @@ void MainWindow::buildWidgets() rcViewDockWidget = new QDockWidget(tr("Radio Control"), this); rcViewDockWidget->setWidget( new QGCRemoteControlView(this) ); + headUpDockWidget = new QDockWidget(tr("Control Indicator"), this); + headUpDockWidget->setWidget( new HUD(320, 240, this)); + // Dialogue widgets //FIXME: free memory in destructor joystick = new JoystickInput(); @@ -203,8 +206,13 @@ void MainWindow::connectWidgets() // add Waypoint widget in the WaypointList widget when mouse clicked connect(mapWidget, SIGNAL(captureMapCoordinateClick(QPointF)), waypointsDockWidget->widget(), SLOT(addWaypointMouse(QPointF))); // it notifies that a waypoint global goes to do create - connect(mapWidget, SIGNAL(createGlobalWP(bool)), waypointsDockWidget->widget(), SLOT(setIsWPGlobal(bool))); + connect(mapWidget, SIGNAL(createGlobalWP(bool, QPointF)), waypointsDockWidget->widget(), SLOT(setIsWPGlobal(bool, QPointF))); connect(mapWidget, SIGNAL(sendGeometryEndDrag(QPointF,int)), waypointsDockWidget->widget(), SLOT(waypointGlobalChanged(QPointF,int)) ); + + // it notifies that a waypoint global goes to do create and a map graphic too + connect(waypointsDockWidget->widget(), SIGNAL(createWaypointAtMap(QPointF)), mapWidget, SLOT(createWaypointGraphAtMap(QPointF))); + // it notifies that a waypoint global change it´s position by spinBox on Widget WaypointView + connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float))); } } @@ -213,7 +221,6 @@ void MainWindow::arrangeCenterStack() QStackedWidget *centerStack = new QStackedWidget(this); if (!centerStack) return; - if (linechartWidget) centerStack->addWidget(linechartWidget); if (protocolWidget) centerStack->addWidget(protocolWidget); if (mapWidget) centerStack->addWidget(mapWidget); @@ -362,7 +369,7 @@ void MainWindow::connectActions() connect(ui.actionShow_MAVLink_view, SIGNAL(triggered()), this, SLOT(loadMAVLinkView())); connect(ui.actionShow_data_analysis_view, SIGNAL(triggered()), this, SLOT(loadDataView())); connect(ui.actionStyleConfig, SIGNAL(triggered()), this, SLOT(reloadStylesheet())); - + connect(ui.actionGlobalOperatorView, SIGNAL(triggered()), this, SLOT(loadGlobalOperatorView())); connect(ui.actionOnline_documentation, SIGNAL(triggered()), this, SLOT(showHelp())); connect(ui.actionCredits_Developers, SIGNAL(triggered()), this, SLOT(showCredits())); connect(ui.actionProject_Roadmap, SIGNAL(triggered()), this, SLOT(showRoadMap())); @@ -808,6 +815,7 @@ void MainWindow::loadOperatorView() centerStack->setCurrentWidget(mapWidget); } } + // UAS CONTROL if (controlDockWidget) { @@ -865,6 +873,83 @@ void MainWindow::loadOperatorView() this->show(); } +void MainWindow::loadGlobalOperatorView() +{ + clearView(); + + // MAP + if (mapWidget) + { + QStackedWidget *centerStack = dynamic_cast(centralWidget()); + if (centerStack) + { + centerStack->setCurrentWidget(mapWidget); + } + } + + // UAS CONTROL + if (controlDockWidget) + { + addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget); + controlDockWidget->show(); + } + + // UAS LIST + if (listDockWidget) + { + addDockWidget(Qt::BottomDockWidgetArea, listDockWidget); + listDockWidget->show(); + } + + // UAS STATUS + if (infoDockWidget) + { + addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget); + infoDockWidget->show(); + } + + // WAYPOINT LIST + if (waypointsDockWidget) + { + addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget); + waypointsDockWidget->show(); + } + +// // HORIZONTAL SITUATION INDICATOR +// if (hsiDockWidget) +// { +// HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() ); +// if (hsi) +// { +// addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget); +// hsiDockWidget->show(); +// hsi->start(); +// } +// } + + // PROCESS CONTROL + if (watchdogControlDockWidget) + { + addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget); + watchdogControlDockWidget->show(); + } + + // HEAD UP DISPLAY + if (headUpDockWidget) + { + addDockWidget(Qt::RightDockWidgetArea, headUpDockWidget); + // FIXME Replace with default ->show() call + HUD* hud = dynamic_cast(headUpDockWidget->widget()); + + if (hud) + { + headUpDockWidget->show(); + hud->start(); + } + } + +} + void MainWindow::load3DView() { clearView(); diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index d9671f4..1ad588c 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -122,6 +122,8 @@ public slots: void loadDataView(); /** @brief Load data view, allowing to plot flight data */ void loadDataView(QString fileName); + /** @brief Load view for global operator, allowing to flight on earth */ + void loadGlobalOperatorView(); /** @brief Show the online help for users */ void showHelp(); @@ -174,6 +176,7 @@ protected: QPointer headDown1DockWidget; QPointer headDown2DockWidget; QPointer watchdogControlDockWidget; + QPointer headUpDockWidget; QPointer hsiDockWidget; QPointer rcViewDockWidget; diff --git a/src/ui/MainWindow.ui b/src/ui/MainWindow.ui index fadf5e8..75f7eb0 100644 --- a/src/ui/MainWindow.ui +++ b/src/ui/MainWindow.ui @@ -76,6 +76,7 @@ + @@ -308,6 +309,15 @@ Credits / Developers + + + + :/images/categories/applications-internet.svg:/images/categories/applications-internet.svg + + + Show Global operator view + + diff --git a/src/ui/MapWidget.cc b/src/ui/MapWidget.cc index 37d1b8e..f866f7f 100644 --- a/src/ui/MapWidget.cc +++ b/src/ui/MapWidget.cc @@ -47,10 +47,13 @@ MapWidget::MapWidget(QWidget *parent) : zoomLevel(0), uasIcons(), uasTrails(), + mav(NULL), m_ui(new Ui::MapWidget) { m_ui->setupUi(this); + waypointIsDrag = false; + // Accept focus by clicking or keyboard this->setFocusPolicy(Qt::StrongFocus); @@ -314,8 +317,9 @@ void MapWidget::createPathButtonClicked(bool checked) this->setCursor(Qt::PointingHandCursor); mc->setMouseMode(qmapcontrol::MapControl::None); + // emit signal start to create a Waypoint global - emit createGlobalWP(true); + emit createGlobalWP(true, mc->currentCoordinate()); // // Clear the previous WP track // // TODO: Move this to an actual clear track button and add a warning dialog @@ -337,9 +341,11 @@ void MapWidget::createPathButtonClicked(bool checked) } -void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordinate){ +void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordinate) +{ - if (QEvent::MouseButtonRelease == event->type() && createPath->isChecked()){ + if (QEvent::MouseButtonRelease == event->type() && createPath->isChecked()) + { // Create waypoint name QString str; @@ -373,18 +379,45 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina } } -void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){ +void MapWidget::createWaypointGraphAtMap(const QPointF coordinate) +{ + // Create waypoint name + QString str; + + str = QString("%1").arg(path->numberOfPoints()); + + // create the WP and set everything in the LineString to display the path + CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str); + mc->layer("Waypoints")->addGeometry(tempCirclePoint); + + Point* tempPoint = new Point(coordinate.x(), coordinate.y(),str); + wps.append(tempPoint); + path->addPoint(tempPoint); + + wpIndex.insert(str,tempPoint); + + // Refresh the screen + mc->updateRequestNew(); + +//// // emit signal mouse was clicked +// emit captureMapCoordinateClick(coordinate); +} + +void MapWidget::captureGeometryClick(Geometry* geom, QPoint point) +{ Q_UNUSED(geom); Q_UNUSED(point); mc->setMouseMode(qmapcontrol::MapControl::None); - } -void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){ +void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate) +{ Q_UNUSED(coordinate); + waypointIsDrag = true; + // Refresh the screen mc->updateRequestNew(); @@ -412,6 +445,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){ void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate) { + waypointIsDrag = false; mc->setMouseMode(qmapcontrol::MapControl::Panning); @@ -603,10 +637,35 @@ void MapWidget::clearPath() wpIndex.clear(); mc->updateRequestNew(); - // si el boton de crear wp globales esta activo desactivarlo llamando a su evento clicket + if(createPath->isChecked()) { createPath->click(); } } + +void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon) +{ + if(!waypointIsDrag) + { + qDebug() <<"indice WP= "<setCoordinate(coordinate); + + point2Find = dynamic_cast (mc->layer("Waypoints")->get_Geometry(index)); + point2Find->setCoordinate(coordinate); + + // Refresh the screen + mc->updateRequestNew(); + } + + +} + diff --git a/src/ui/MapWidget.h b/src/ui/MapWidget.h index 35afb70..450ed25 100644 --- a/src/ui/MapWidget.h +++ b/src/ui/MapWidget.h @@ -66,6 +66,7 @@ public slots: //ROCA void clearPath(); + void changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon); protected: void changeEvent(QEvent* e); @@ -106,6 +107,7 @@ protected: protected slots: void captureMapClick (const QMouseEvent* event, const QPointF coordinate); + void createWaypointGraphAtMap (const QPointF coordinate); void createPathButtonClicked(bool checked); void captureGeometryClick(Geometry*, QPoint); void mapproviderSelected(QAction* action); @@ -114,10 +116,11 @@ protected: + signals: //void movePoint(QPointF newCoord); void captureMapCoordinateClick(const QPointF coordinate); //ROCA - void createGlobalWP(bool value); + void createGlobalWP(bool value, QPointF centerCoordinate); void sendGeometryEndDrag(const QPointF coordinate, const int index); @@ -127,6 +130,7 @@ private: QHash wpIndex; qmapcontrol::LineString* path; QPen* pointPen; + bool waypointIsDrag; }; #endif // MAPWIDGET_H diff --git a/src/ui/WaypointGlobalView.cc b/src/ui/WaypointGlobalView.cc new file mode 100644 index 0000000..44a9202 --- /dev/null +++ b/src/ui/WaypointGlobalView.cc @@ -0,0 +1,462 @@ +#include "WaypointGlobalView.h" +#include "ui_WaypointGlobalView.h" + +#include + +WaypointGlobalView::WaypointGlobalView(Waypoint* wp,QWidget *parent) : + QWidget(parent), + ui(new Ui::WaypointGlobalView) +{ + ui->setupUi(this); + this->wp = wp; + + ui->m_orbitalSpinBox->hide(); + + // Read values and set user interface + updateValues(); + + connect(ui->m_orbitalSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setOrbit(double))); + connect(ui->m_heigthSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double))); + + //for spinBox Latitude + connect(ui->m_latitudGrados_spinBox, SIGNAL(valueChanged(int)), this, SLOT(updateLatitudeWP(int))); + connect(ui->m_latitudMinutos_spinBox, SIGNAL(valueChanged(double)), this, SLOT(updateLatitudeMinuteWP(double))); + connect(ui->m_dirLatitudeN_radioButton, SIGNAL(clicked()), this, SLOT(changeDirectionLatitudeWP())); + connect(ui->m_dirLatitudeS_radioButton, SIGNAL(clicked()), this, SLOT(changeDirectionLatitudeWP())); + + //for spinBox Longitude + connect(ui->m_longitudGrados_spinBox, SIGNAL(valueChanged(int)), this, SLOT(updateLongitudeWP(int))); + connect(ui->m_longitudMinutos_spinBox, SIGNAL(valueChanged(double)), this, SLOT(updateLongitudeMinuteWP(double))); + connect(ui->m_dirLongitudeW_radioButton, SIGNAL(clicked()), this, SLOT(changeDirectionLongitudeWP())); + connect(ui->m_dirLongitudeE_radioButton, SIGNAL(clicked()), this, SLOT(changeDirectionLongitudeWP())); + + + + connect(ui->m_orbitCheckBox, SIGNAL(stateChanged(int)), this, SLOT(changeOrbitalState(int))); + + + + + +// connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double))); +// connect(m_ui->ySpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double))); +// connect(m_ui->zSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double))); + +// //hidden degree to radian conversion of the yaw angle +// connect(m_ui->yawSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setYaw(int))); +// connect(this, SIGNAL(setYaw(double)), wp, SLOT(setYaw(double))); + +// connect(m_ui->upButton, SIGNAL(clicked()), this, SLOT(moveUp())); +// connect(m_ui->downButton, SIGNAL(clicked()), this, SLOT(moveDown())); +// connect(m_ui->removeButton, SIGNAL(clicked()), this, SLOT(remove())); + +// connect(m_ui->autoContinue, SIGNAL(stateChanged(int)), this, SLOT(changedAutoContinue(int))); +// connect(m_ui->selectedBox, SIGNAL(stateChanged(int)), this, SLOT(changedCurrent(int))); + +// +// connect(m_ui->holdTimeSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setHoldTime(int))); +} + +WaypointGlobalView::~WaypointGlobalView() +{ + delete ui; +} + +void WaypointGlobalView::updateValues() +{ + + int gradoLat, gradoLon; + float minLat, minLon; + QString dirLat, dirLon; + + getLatitudeGradoMin(wp->getY(), &gradoLat, &minLat, &dirLat); + getLongitudGradoMin(wp->getX(), &gradoLon, &minLon, &dirLon); + + //latitude on spinBox + ui->m_latitudGrados_spinBox->setValue(gradoLat); + ui->m_latitudMinutos_spinBox->setValue(minLat); + if(dirLat == "N") + { + ui->m_dirLatitudeN_radioButton->setChecked(true); + ui->m_dirLatitudeS_radioButton->setChecked(false); + } + else + { + ui->m_dirLatitudeS_radioButton->setChecked(true); + ui->m_dirLatitudeN_radioButton->setChecked(false); + + } + + //longitude on spinBox + ui->m_longitudGrados_spinBox->setValue(gradoLon); + ui->m_longitudMinutos_spinBox->setValue(minLon); + if(dirLon == "W") + { + ui->m_dirLongitudeW_radioButton->setChecked(true); + ui->m_dirLongitudeE_radioButton->setChecked(false); + } + else + { + ui->m_dirLongitudeE_radioButton->setChecked(true); + ui->m_dirLongitudeW_radioButton->setChecked(false); + + } + + ui->idWP_label->setText(QString("WP-%1").arg(wp->getId())); + + +} + +void WaypointGlobalView::changeEvent(QEvent *e) +{ + switch (e->type()) { + case QEvent::LanguageChange: + ui->retranslateUi(this); + break; + default: + break; + } +} + +void WaypointGlobalView::remove() +{ + emit removeWaypoint(wp); + delete this; +} + +QString WaypointGlobalView::getLatitudString(float latitud) +{ + QString tempNS =""; + QString stringLatitudTemp = ""; + + float minutos = 0; + float grados = 0; + float entero = 0; + float dec = 0; + + if (latitud<0){tempNS="S"; latitud = latitud * -1;} + else {tempNS="N";} + + if(latitud< 90 || latitud > -90) + { + dec = latitud - (entero = ::floor(latitud));; + minutos = dec * 60; + grados = entero; + if(grados < 0) grados = grados * (-1); + if(minutos < 0) minutos = minutos * (-1); + + stringLatitudTemp = QString::number(grados)+ " ° "+ QString::number(minutos)+"' "+ tempNS; + + return stringLatitudTemp; + } + else + { + stringLatitudTemp = "erroneous latitude"; + return stringLatitudTemp; + } + +} + +QString WaypointGlobalView::getLongitudString(float longitud) +{ + QString tempEW =""; + QString stringLongitudTemp = ""; + + float minutos = 0; + float grados = 0; + float entero = 0; + float dec = 0; + + if (longitud<0){tempEW="W"; longitud = longitud * -1;} + else {tempEW="E";} + + if(longitud<180 || longitud > -180) + { + dec = longitud - (entero = ::floor(longitud));; + minutos = dec * 60; + grados = entero; + if(grados < 0) grados = grados * (-1); + if(minutos < 0) minutos = minutos * (-1); + + stringLongitudTemp = QString::number(grados)+ " ° "+ QString::number(minutos)+"' "+ tempEW; + + return stringLongitudTemp; + } + else + { + stringLongitudTemp = "erroneous longitude"; + return stringLongitudTemp; + } +} + +void WaypointGlobalView::changeOrbitalState(int state) +{ + Q_UNUSED(state); + + if(ui->m_orbitCheckBox->isChecked()) + { + ui->m_orbitalSpinBox->setEnabled(true); + ui->m_orbitalSpinBox->show(); + } + else + { + ui->m_orbitalSpinBox->setEnabled(false); + ui->m_orbitalSpinBox->hide(); + } +} + +void WaypointGlobalView::getLatitudeGradoMin(float latitud, int *gradoLat, float *minLat, QString *dirLat) +{ + + float minutos = 0; + float grados = 0; + float entero = 0; + float dec = 0; + + if (latitud<0){*dirLat="S"; latitud = latitud * -1;} + else {*dirLat="N";} + + if(latitud< 90 || latitud > -90) + { + dec = latitud - (entero = ::floor(latitud));; + minutos = dec * 60; + grados = entero; + if(grados < 0) grados = grados * (-1); + if(minutos < 0) minutos = minutos * (-1); + + *gradoLat = grados; + *minLat = minutos; + + + } + else + { + *gradoLat = -1; + *minLat = -1; + *dirLat="N/A"; + + } + +} + +void WaypointGlobalView::getLongitudGradoMin(float longitud, int *gradoLon, float *minLon, QString *dirLon) +{ + + float minutos = 0; + float grados = 0; + float entero = 0; + float dec = 0; + + if (longitud<0){*dirLon="W"; longitud = longitud * -1;} + else {*dirLon="E";} + + if(longitud<180 || longitud > -180) + { + dec = longitud - (entero = ::floor(longitud));; + minutos = dec * 60; + grados = entero; + if(grados < 0) grados = grados * (-1); + if(minutos < 0) minutos = minutos * (-1); + + *gradoLon = grados; + *minLon = minutos; + + } + else + { + *gradoLon = -1; + *minLon = -1; + *dirLon="N/A"; + } +} + +void WaypointGlobalView::updateCoordValues(float lat, float lon) +{ + +} + +void WaypointGlobalView::updateLatitudeWP(int value) +{ + Q_UNUSED(value); + + + int gradoLat; + float minLat; + float Latitud; + QString dirLat; + + gradoLat = ui->m_latitudGrados_spinBox->value(); + minLat = ui->m_latitudMinutos_spinBox->value(); + if(ui->m_dirLatitudeN_radioButton->isChecked()) + { + dirLat = "N"; + } + else + { + dirLat = "S"; + } + //dirLat = ui->m_dirLatitud_label->text(); + + Latitud = gradoLat + (minLat/60); + if(dirLat == "S"){Latitud = Latitud * -1;} + + wp->setY(Latitud); + + //emit signal waypoint position was changed + + emit changePositionWP(wp); + +} + +void WaypointGlobalView::updateLatitudeMinuteWP(double value) +{ + Q_UNUSED(value); + + int gradoLat; + float minLat; + float Latitud; + QString dirLat; + + gradoLat = ui->m_latitudGrados_spinBox->value(); + minLat = ui->m_latitudMinutos_spinBox->value(); + //dirLat = ui->m_dirLatitud_label->text(); + if(ui->m_dirLatitudeN_radioButton->isChecked()) + { + dirLat = "N"; + } + else + { + dirLat = "S"; + } + + Latitud = gradoLat + (minLat/60); + if(dirLat == "S"){Latitud = Latitud * -1;} + + wp->setY(Latitud); + + //emit signal waypoint position was changed + emit changePositionWP(wp); + + +} + +void WaypointGlobalView::updateLongitudeWP(int value) +{ + Q_UNUSED(value); + + int gradoLon; + float minLon; + float Longitud; + QString dirLon; + + gradoLon = ui->m_longitudGrados_spinBox->value(); + minLon = ui->m_longitudMinutos_spinBox->value(); + // dirLon = ui->m_dirLongitud_label->text(); + if(ui->m_dirLongitudeW_radioButton->isChecked()) + { + dirLon = "W"; + } + else + { + dirLon = "E"; + } + + Longitud = gradoLon + (minLon/60); + if(dirLon == "W"){Longitud = Longitud * -1;} + + wp->setX(Longitud); + + //emit signal waypoint position was changed + emit changePositionWP(wp); + + +} + + + +void WaypointGlobalView::updateLongitudeMinuteWP(double value) +{ + Q_UNUSED(value); + + int gradoLon; + float minLon; + float Longitud; + QString dirLon; + + gradoLon = ui->m_longitudGrados_spinBox->value(); + minLon = ui->m_longitudMinutos_spinBox->value(); + // dirLon = ui->m_dirLongitud_label->text(); + if(ui->m_dirLongitudeW_radioButton->isChecked()) + { + dirLon = "W"; + } + else + { + dirLon = "E"; + } + + Longitud = gradoLon + (minLon/60); + if(dirLon == "W"){Longitud = Longitud * -1;} + + wp->setX(Longitud); + + //emit signal waypoint position was changed + emit changePositionWP(wp); + +} + +void WaypointGlobalView::changeDirectionLatitudeWP() +{ + if(ui->m_dirLatitudeN_radioButton->isChecked()) + { + if(wp->getY() < 0) + { + wp->setY(wp->getY()* -1); + //emit signal waypoint position was changed + emit changePositionWP(wp); + } + + } + if(ui->m_dirLatitudeS_radioButton->isChecked()) + { + if(wp->getY() > 0) + { + wp->setY(wp->getY()*-1); + //emit signal waypoint position was changed + emit changePositionWP(wp); + + } + + } + +} + +void WaypointGlobalView::changeDirectionLongitudeWP() +{ + if(ui->m_dirLongitudeW_radioButton->isChecked()) + { + if(wp->getX() > 0) + { + wp->setX(wp->getX()*-1); + //emit signal waypoint position was changed + emit changePositionWP(wp); + } + + } + + if(ui->m_dirLongitudeE_radioButton->isChecked()) + { + if(wp->getX() < 0) + { + wp->setX(wp->getX()*-1); + //emit signal waypoint position was changed + emit changePositionWP(wp); + } + + } + + + +} + + diff --git a/src/ui/WaypointGlobalView.cpp b/src/ui/WaypointGlobalView.cpp deleted file mode 100644 index b57df7f..0000000 --- a/src/ui/WaypointGlobalView.cpp +++ /dev/null @@ -1,155 +0,0 @@ -#include "WaypointGlobalView.h" -#include "ui_WaypointGlobalView.h" - -#include - -WaypointGlobalView::WaypointGlobalView(Waypoint* wp,QWidget *parent) : - QWidget(parent), - ui(new Ui::WaypointGlobalView) -{ - ui->setupUi(this); - this->wp = wp; - - ui->m_orbitalSpinBox->hide(); - - connect(ui->m_orbitalSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setOrbit(double))); - connect(ui->m_heigthSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double))); - - connect(ui->m_orbitCheckBox, SIGNAL(stateChanged(int)), this, SLOT(changeOrbitalState(int))); - - - // Read values and set user interface - updateValues(); - - -// connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double))); -// connect(m_ui->ySpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double))); -// connect(m_ui->zSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double))); - -// //hidden degree to radian conversion of the yaw angle -// connect(m_ui->yawSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setYaw(int))); -// connect(this, SIGNAL(setYaw(double)), wp, SLOT(setYaw(double))); - -// connect(m_ui->upButton, SIGNAL(clicked()), this, SLOT(moveUp())); -// connect(m_ui->downButton, SIGNAL(clicked()), this, SLOT(moveDown())); -// connect(m_ui->removeButton, SIGNAL(clicked()), this, SLOT(remove())); - -// connect(m_ui->autoContinue, SIGNAL(stateChanged(int)), this, SLOT(changedAutoContinue(int))); -// connect(m_ui->selectedBox, SIGNAL(stateChanged(int)), this, SLOT(changedCurrent(int))); - -// -// connect(m_ui->holdTimeSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setHoldTime(int))); -} - -WaypointGlobalView::~WaypointGlobalView() -{ - delete ui; -} - -void WaypointGlobalView::updateValues() -{ - ui->m_latitudtextEdit->setText(getLatitudString(wp->getY())); - ui->m_longitudtextEdit->setText(getLongitudString(wp->getX())); - ui->idWP_label->setText(QString("%1").arg(wp->getId()));\ - -} - -void WaypointGlobalView::changeEvent(QEvent *e) -{ - switch (e->type()) { - case QEvent::LanguageChange: - ui->retranslateUi(this); - break; - default: - break; - } -} - -void WaypointGlobalView::remove() -{ - emit removeWaypoint(wp); - delete this; -} - -QString WaypointGlobalView::getLatitudString(float latitud) -{ - QString tempNS =""; - QString stringLatitudTemp = ""; - - float minutos = 0; - float grados = 0; - float entero = 0; - float dec = 0; - - if (latitud<0){tempNS="S"; latitud = latitud * -1;} - else {tempNS="N";} - - if(latitud< 90 || latitud > -90) - { - dec = latitud - (entero = ::floor(latitud));; - minutos = dec * 60; - grados = entero; - if(grados < 0) grados = grados * (-1); - if(minutos < 0) minutos = minutos * (-1); - - stringLatitudTemp = QString::number(grados)+ " ° "+ QString::number(minutos)+"' "+ tempNS; - - return stringLatitudTemp; - } - else - { - stringLatitudTemp = "erroneous latitude"; - return stringLatitudTemp; - } - -} - -QString WaypointGlobalView::getLongitudString(float longitud) -{ - QString tempEW =""; - QString stringLongitudTemp = ""; - - float minutos = 0; - float grados = 0; - float entero = 0; - float dec = 0; - - if (longitud<0){tempEW="W"; longitud = longitud * -1;} - else {tempEW="E";} - - if(longitud<180 || longitud > -180) - { - dec = longitud - (entero = ::floor(longitud));; - minutos = dec * 60; - grados = entero; - if(grados < 0) grados = grados * (-1); - if(minutos < 0) minutos = minutos * (-1); - - stringLongitudTemp = QString::number(grados)+ " ° "+ QString::number(minutos)+"' "+ tempEW; - - return stringLongitudTemp; - } - else - { - stringLongitudTemp = "erroneous longitude"; - return stringLongitudTemp; - } -} - -void WaypointGlobalView::changeOrbitalState(int state) -{ - Q_UNUSED(state); - - if(ui->m_orbitCheckBox->isChecked()) - { - ui->m_orbitalSpinBox->setEnabled(true); - ui->m_orbitalSpinBox->show(); - } - else - { - ui->m_orbitalSpinBox->setEnabled(false); - ui->m_orbitalSpinBox->hide(); - } -} - - diff --git a/src/ui/WaypointGlobalView.h b/src/ui/WaypointGlobalView.h index 293b8b1..02fc795 100644 --- a/src/ui/WaypointGlobalView.h +++ b/src/ui/WaypointGlobalView.h @@ -22,12 +22,30 @@ public slots: void remove(); QString getLatitudString(float lat); QString getLongitudString(float lon); + void getLatitudeGradoMin(float lat, int *gradoLat, float *minLat, QString *dirLat); + void getLongitudGradoMin(float lon, int *gradoLon, float *minLon, QString *dirLon); void changeOrbitalState(int state); + void updateCoordValues(float lat, float lon); + + + + //update latitude + void updateLatitudeWP(int value); + void updateLatitudeMinuteWP(double value); + void changeDirectionLatitudeWP(); + + //update longitude + void updateLongitudeWP(int value); + void updateLongitudeMinuteWP(double value); + void changeDirectionLongitudeWP(); + signals: void removeWaypoint(Waypoint*); + void changePositionWP(Waypoint*); + protected: virtual void changeEvent(QEvent *e); diff --git a/src/ui/WaypointGlobalView.ui b/src/ui/WaypointGlobalView.ui index 8a04282..d3677b5 100644 --- a/src/ui/WaypointGlobalView.ui +++ b/src/ui/WaypointGlobalView.ui @@ -6,12 +6,12 @@ 0 0 - 774 - 184 + 824 + 79 - + 0 0 @@ -48,21 +48,21 @@ margin-top: 1ex; /* leave space at the top for the title */ margin: 0px; } - QGroupBox::title { - subcontrol-origin: margin; - subcontrol-position: top center; /* position at the top center */ - margin: 0 3px 0px 3px; - padding: 0 3px 0px 0px; - font: bold 8px; - } + QGroupBox::title { +     subcontrol-origin: margin; +     subcontrol-position: top center; /* position at the top center */ +     margin: 0 3px 0px 3px; +     padding: 0 3px 0px 0px; +     font: bold 8px; + } QGroupBox#heartbeatIcon { background-color: red; } - QDockWidget { + QDockWidget { font: bold; - border: 1px solid #32345E; +    border: 1px solid #32345E; } QPushButton { @@ -85,25 +85,25 @@ QPushButton:pressed { QPushButton#landButton { color: #000000; background: qlineargradient(x1:0, y1:0, x2:0, y2:1, - stop:0 #ffee01, stop:1 #ae8f00) url("ICONDIR/control/emergency-button.png"); +                             stop:0 #ffee01, stop:1 #ae8f00) url("ICONDIR/control/emergency-button.png"); } QPushButton:pressed#landButton { color: #000000; background: qlineargradient(x1:0, y1:0, x2:0, y2:1, - stop:0 #bbaa00, stop:1 #a05b00) url("ICONDIR/control/emergency-button.png"); +                             stop:0 #bbaa00, stop:1 #a05b00) url("ICONDIR/control/emergency-button.png"); } QPushButton#killButton { color: #000000; background: qlineargradient(x1:0, y1:0, x2:0, y2:1, - stop:0 #ffb917, stop:1 #b37300) url("ICONDIR/control/emergency-button.png"); +                             stop:0 #ffb917, stop:1 #b37300) url("ICONDIR/control/emergency-button.png"); } QPushButton:pressed#killButton { color: #000000; background: qlineargradient(x1:0, y1:0, x2:0, y2:1, - stop:0 #bb8500, stop:1 #903000) url("ICONDIR/control/emergency-button.png"); +                             stop:0 #bb8500, stop:1 #903000) url("ICONDIR/control/emergency-button.png"); } QProgressBar { @@ -143,10 +143,7 @@ QProgressBar::chunk#thrustBar { background-color: orange; } - - - QLayout::SetDefaultConstraint - + 0 @@ -164,279 +161,699 @@ QProgressBar::chunk#thrustBar { - - + + 2 - + + 4 + + 2 - + + 4 + + + + + 10 + 75 + true + + WP_id - + Qt::Horizontal - - QSizePolicy::MinimumExpanding - - 2 - 0 + 16 + 20 - - - - Lat: + + + + + 75 + true + + + + + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + true + + + + 2 + + + 2 + + + + + + 10 + 75 + true + + + + LAT: + + + + + + + ° + + + 0 + + + 89 + + + + + + + ' + + + 0.000000000000000 + + + 59.990000000000002 + + + 0.010000000000000 + + + + + + + S + + + + + + + N + + + true + + + + - - - - - + + Qt::Horizontal - 2 - 0 + 11 + 20 - - - - Lon: + + + + + 75 + true + + + + + + + 2 + + + 2 + + + + + + 10 + 75 + true + + + + LON: + + + + + + + ° + + + -179 + + + 179 + + + + + + + ' + + + 0.000000000000000 + + + 59.990000000000002 + + + 0.010000000000000 + + + + + + + E + + + + + + + W + + + true + + + + - - - - - + + Qt::Horizontal - - QSizePolicy::MinimumExpanding - - 2 - 0 + 16 + 20 - - - - Heigth - - - - - - - - - - - - - - - 69 - 69 - 69 - - - - - - - 37 - 37 - 40 - - - - - - - 69 - 69 - 69 - - - - - - - 69 - 69 - 69 - - - - - - - 37 - 37 - 40 - - - - - - - 37 - 37 - 40 - - - - - - - - - 69 - 69 - 69 - - - - - - - 37 - 37 - 40 - - - - - - - 69 - 69 - 69 - - - - - - - 69 - 69 - 69 - - - - - - - 37 - 37 - 40 - - - - - - - 37 - 37 - 40 - - - - - - - - - 69 - 69 - 69 - - - - - - - 37 - 37 - 40 - - - - - - - 69 - 69 - 69 - - - - - - - 69 - 69 - 69 - - - - - - - 37 - 37 - 40 - - - - - - - 37 - 37 - 40 - - - - - - - - Orbital - - - - - - - true + + + + + + + 2 + + + 2 + + + + + Alt + + + + + + + + + + Orbital + + + + + + + + + + + + 69 + 69 + 69 + + + + + + + 37 + 37 + 40 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 127 + 127 + 127 + + + + + + + 170 + 170 + 170 + + + + + + + 69 + 69 + 69 + + + + + + + 255 + 255 + 255 + + + + + + + 69 + 69 + 69 + + + + + + + 37 + 37 + 40 + + + + + + + 37 + 37 + 40 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 69 + 69 + 69 + + + + + + + 37 + 37 + 40 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 127 + 127 + 127 + + + + + + + 170 + 170 + 170 + + + + + + + 69 + 69 + 69 + + + + + + + 255 + 255 + 255 + + + + + + + 69 + 69 + 69 + + + + + + + 37 + 37 + 40 + + + + + + + 37 + 37 + 40 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 69 + 69 + 69 + + + + + + + 37 + 37 + 40 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 127 + 127 + 127 + + + + + + + 170 + 170 + 170 + + + + + + + 69 + 69 + 69 + + + + + + + 255 + 255 + 255 + + + + + + + 69 + 69 + 69 + + + + + + + 37 + 37 + 40 + + + + + + + 37 + 37 + 40 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + + + + + + + true + + + + diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc index 25b7171..1f7f133 100644 --- a/src/ui/WaypointList.cc +++ b/src/ui/WaypointList.cc @@ -39,6 +39,7 @@ This file is part of the PIXHAWK project #include #include "WaypointGlobalView.h" #include +#include WaypointList::WaypointList(QWidget *parent, UASInterface* uas) : QWidget(parent), @@ -90,6 +91,9 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) : this->setVisible(false); isGlobalWP = false; isLocalWP = false; + centerMapCoordinate.setX(0.0); + centerMapCoordinate.setY(0.0); + } WaypointList::~WaypointList() @@ -168,24 +172,44 @@ void WaypointList::add() { if (uas) { - + if(isGlobalWP) + { const QVector &waypoints = uas->getWaypointManager().getWaypointList(); if (waypoints.size() > 0) { Waypoint *last = waypoints.at(waypoints.size()-1); - Waypoint *wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime()); + Waypoint *wp = new Waypoint(0, centerMapCoordinate.x(), centerMapCoordinate.y(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime()); uas->getWaypointManager().localAddWaypoint(wp); } else { - Waypoint *wp = new Waypoint(0, 1.1, 1.1, -0.8, 0.0, true, true, 0.15, 2000); + Waypoint *wp = new Waypoint(0, centerMapCoordinate.x(), centerMapCoordinate.y(), -0.8, 0.0, true, true, 0.15, 2000); uas->getWaypointManager().localAddWaypoint(wp); } - isLocalWP = true; + emit createWaypointAtMap(centerMapCoordinate); + } + else + { + + const QVector &waypoints = uas->getWaypointManager().getWaypointList(); + if (waypoints.size() > 0) + { + Waypoint *last = waypoints.at(waypoints.size()-1); + Waypoint *wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime()); + uas->getWaypointManager().localAddWaypoint(wp); + } + else + { + + isLocalWP = true; + Waypoint *wp = new Waypoint(0, 1.1, 1.1, -0.8, 0.0, true, true, 0.15, 2000); + uas->getWaypointManager().localAddWaypoint(wp); + } + } } } @@ -301,9 +325,11 @@ void WaypointList::waypointListChanged() { WaypointGlobalView* wpview = new WaypointGlobalView(wp, this); wpGlobalViews.insert(wp, wpview); + connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*))); + connect(wpview, SIGNAL(changePositionWP(Waypoint*)), this, SLOT(changeWPPositionBySpinBox(Waypoint*))); // connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*))); // connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*))); - connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*))); + // connect(wpview, SIGNAL(changePositionWP(Waypoint*)), this, SLOT(waypointGlobalPositionChanged(Waypoint*))); // connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16))); // connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16))); } @@ -498,13 +524,16 @@ void WaypointList::addWaypointMouse(QPointF coordinate) Waypoint *wp = new Waypoint(0, coordinate.x(), coordinate.y(), -0.8, 0.0, true, true, 0.15, 2000); uas->getWaypointManager().localAddWaypoint(wp); } + + } } - /** @brief it notifies that a global waypoint goes to do created */ -void WaypointList::setIsWPGlobal(bool value) + /** @brief Notifies the user that a global waypoint will be created */ +void WaypointList::setIsWPGlobal(bool value, QPointF centerCoordinate) { + centerMapCoordinate = centerCoordinate; if(isLocalWP) @@ -512,18 +541,21 @@ void WaypointList::setIsWPGlobal(bool value) if(wpViews.size()!= 0) { - int ret = QMessageBox::warning(this, tr("My Application"), - tr("There are Waypoints local created.\n" + int ret = QMessageBox::warning(this, tr("QGroundControl"), + tr("There are Local Waypoints created.\n" "Do you want to clear them?"), QMessageBox::Ok | QMessageBox::Cancel); if(ret) { clearLocalWPWidget(); - isGlobalWP = value; - isLocalWP = !(value); + + } + } + isLocalWP = !value; + isGlobalWP = value; } @@ -556,6 +588,19 @@ void WaypointList::waypointGlobalChanged(QPointF coordinate, int indexWP) } +///** @brief The MapWidget informs that a waypoint global was changed on the map */ + +//void WaypointList::waypointGlobalPositionChanged(Waypoint* wp) +//{ +// QPointF coordinate; +// coordinate.setX(wp->getX()); +// coordinate.setY(wp->getY()); + +// emit ChangeWaypointGlobalPosition(wp->getId(), coordinate); + + +//} + void WaypointList::clearLocalWPWidget() { if (uas) @@ -571,3 +616,9 @@ void WaypointList::clearLocalWPWidget() } } } + +void WaypointList::changeWPPositionBySpinBox(Waypoint *wp) +{ + + emit changePositionWPGlobalBySpinBox(wp->getId(), wp->getY(), wp->getX()); +} diff --git a/src/ui/WaypointList.h b/src/ui/WaypointList.h index b4d2593..2432504 100644 --- a/src/ui/WaypointList.h +++ b/src/ui/WaypointList.h @@ -77,7 +77,7 @@ public slots: /** @brief Add a waypoint by mouse click over the map */ void addWaypointMouse(QPointF coordinate); /** @brief it notifies that a global waypoint goes to do created */ - void setIsWPGlobal(bool value); + void setIsWPGlobal(bool value, QPointF centerCoordinate); //Update events @@ -95,6 +95,8 @@ public slots: void clearLocalWPWidget(); + void changeWPPositionBySpinBox(Waypoint* wp); + // Waypoint operations void moveUp(Waypoint* wp); void moveDown(Waypoint* wp); @@ -105,6 +107,9 @@ public slots: signals: void clearPathclicked(); + void createWaypointAtMap(const QPointF coordinate); + // void ChangeWaypointGlobalPosition(int index, QPointF coord); + void changePositionWPGlobalBySpinBox(int indexWP, float lat, float lon); @@ -122,6 +127,7 @@ protected: double mavYaw; bool isGlobalWP; bool isLocalWP; + QPointF centerMapCoordinate; private: Ui::WaypointList *m_ui;