From e605f2dccfaf299f205d2c9f2dad9cc9a2192153 Mon Sep 17 00:00:00 2001 From: tecnosapiens Date: Mon, 13 Sep 2010 14:49:54 -0500 Subject: [PATCH 1/6] separation of the view of the local operator of the view of the global operator adding the view of global operator. add the functionality to draw a waypoints on the map when they are generated from widget waypointlist. --- lib/QMapControl/src/mapcontrol.cpp | 1 + src/ui/MainWindow.cc | 67 ++++++++-- src/ui/MainWindow.h | 2 + src/ui/MainWindow.ui | 10 ++ src/ui/MapWidget.cc | 27 +++- src/ui/MapWidget.h | 3 +- src/ui/WaypointGlobalView.ui | 268 ++++++++++++++++++++++++++++++++++++- src/ui/WaypointList.cc | 37 ++++- src/ui/WaypointList.h | 4 +- 9 files changed, 400 insertions(+), 19 deletions(-) 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/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 0d26071..db61db3 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -103,8 +103,11 @@ MainWindow::MainWindow(QWidget *parent) : // add Waypoint widget in the WaypointList widget when mouse clicked connect(map, SIGNAL(captureMapCoordinateClick(QPointF)), waypoints, SLOT(addWaypointMouse(QPointF))); // it notifies that a waypoint global goes to do create - connect(map, SIGNAL(createGlobalWP(bool)), waypoints, SLOT(setIsWPGlobal(bool))); + connect(map, SIGNAL(createGlobalWP(bool,QPointF)), waypoints, SLOT(setIsWPGlobal(bool, QPointF))); + // it notifies that a waypoint global goes to do create connect(map, SIGNAL(sendGeometryEndDrag(QPointF,int)), waypoints, SLOT(waypointGlobalChanged(QPointF,int)) ); + // it notifies that a waypoint global goes to do create and a map graphic too + connect(waypoints, SIGNAL(createWaypointAtMap(QPointF)), map, SLOT(createWaypointGraphAtMap(QPointF))); } @@ -172,6 +175,7 @@ void MainWindow::arrangeCenterStack() centerStack->addWidget(map); centerStack->addWidget(hud); centerStack->addWidget(dataplot); + centerStack->addWidget(hsi); setCentralWidget(centerStack); } @@ -314,7 +318,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())); @@ -626,8 +630,11 @@ void MainWindow::loadOperatorView() { clearView(); - // MAP - centerStack->setCurrentWidget(map); + + centerStack->setCurrentWidget(hsi); + hsi->start(); + + // UAS CONTROL QDockWidget* container1 = new QDockWidget(tr("Control"), this); @@ -650,10 +657,10 @@ void MainWindow::loadOperatorView() addDockWidget(Qt::BottomDockWidgetArea, container5); // HORIZONTAL SITUATION INDICATOR - QDockWidget* container7 = new QDockWidget(tr("Horizontal Situation Indicator"), this); - container7->setWidget(hsi); - hsi->start(); - addDockWidget(Qt::BottomDockWidgetArea, container7); +// QDockWidget* container7 = new QDockWidget(tr("Horizontal Situation Indicator"), this); +// container7->setWidget(hsi); +// hsi->start(); +// addDockWidget(Qt::BottomDockWidgetArea, container7); // OBJECT DETECTION QDockWidget* container6 = new QDockWidget(tr("Object Recognition"), this); @@ -667,6 +674,50 @@ void MainWindow::loadOperatorView() this->show(); } +void MainWindow::loadGlobalOperatorView() +{ + clearView(); + + // MAP + centerStack->setCurrentWidget(map); + + // UAS CONTROL + QDockWidget* container1 = new QDockWidget(tr("Control"), this); + container1->setWidget(control); + addDockWidget(Qt::LeftDockWidgetArea, container1); + + // UAS LIST + QDockWidget* container4 = new QDockWidget(tr("Unmanned Systems"), this); + container4->setWidget(list); + addDockWidget(Qt::BottomDockWidgetArea, container4); + + // UAS STATUS + QDockWidget* container3 = new QDockWidget(tr("Status Details"), this); + container3->setWidget(info); + addDockWidget(Qt::LeftDockWidgetArea, container3); + + // WAYPOINT LIST + QDockWidget* container5 = new QDockWidget(tr("Waypoint List"), this); + container5->setWidget(waypoints); + addDockWidget(Qt::BottomDockWidgetArea, container5); + + // // HEAD UP DISPLAY + QDockWidget* container6 = new QDockWidget(tr("Control Indicator"), this); + container6->setWidget(hud); + hud->start(); + addDockWidget(Qt::RightDockWidgetArea, container6); + +// // OBJECT DETECTION +// QDockWidget* container6 = new QDockWidget(tr("Object Recognition"), this); +// container6->setWidget(detection); +// addDockWidget(Qt::RightDockWidgetArea, container6); + + // PROCESS CONTROL + QDockWidget* pControl = new QDockWidget(tr("Process Control"), this); + pControl->setWidget(watchdogControl); + addDockWidget(Qt::BottomDockWidgetArea, pControl); + this->show(); +} void MainWindow::loadSettingsView() { clearView(); diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 1ef6f38..d0d709a 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -120,6 +120,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(); diff --git a/src/ui/MainWindow.ui b/src/ui/MainWindow.ui index b9f9674..c05b522 100644 --- a/src/ui/MainWindow.ui +++ b/src/ui/MainWindow.ui @@ -75,6 +75,7 @@ + @@ -318,6 +319,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 5673d50..0804170 100644 --- a/src/ui/MapWidget.cc +++ b/src/ui/MapWidget.cc @@ -310,8 +310,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 @@ -360,6 +361,30 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina } } +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); diff --git a/src/ui/MapWidget.h b/src/ui/MapWidget.h index 7d79949..6adf3f2 100644 --- a/src/ui/MapWidget.h +++ b/src/ui/MapWidget.h @@ -105,6 +105,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); @@ -116,7 +117,7 @@ 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); diff --git a/src/ui/WaypointGlobalView.ui b/src/ui/WaypointGlobalView.ui index 7ad20e3..85ffd0b 100644 --- a/src/ui/WaypointGlobalView.ui +++ b/src/ui/WaypointGlobalView.ui @@ -6,8 +6,8 @@ 0 0 - 869 - 60 + 940 + 56 @@ -144,6 +144,12 @@ QProgressBar::chunk#thrustBar { } + + 0 + + + 0 + @@ -170,7 +176,7 @@ QProgressBar::chunk#thrustBar { - 135 + 10 13 @@ -265,6 +271,19 @@ QProgressBar::chunk#thrustBar { + + + Qt::Horizontal + + + + 86 + 13 + + + + + @@ -287,6 +306,42 @@ QProgressBar::chunk#thrustBar { + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 127 + 127 + 127 + + + + + + + 170 + 170 + 170 + + + @@ -296,6 +351,15 @@ QProgressBar::chunk#thrustBar { + + + + 255 + 255 + 255 + + + @@ -323,6 +387,42 @@ QProgressBar::chunk#thrustBar { + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + @@ -343,6 +443,42 @@ QProgressBar::chunk#thrustBar { + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 127 + 127 + 127 + + + + + + + 170 + 170 + 170 + + + @@ -352,6 +488,15 @@ QProgressBar::chunk#thrustBar { + + + + 255 + 255 + 255 + + + @@ -379,6 +524,42 @@ QProgressBar::chunk#thrustBar { + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + @@ -399,6 +580,42 @@ QProgressBar::chunk#thrustBar { + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 127 + 127 + 127 + + + + + + + 170 + 170 + 170 + + + @@ -408,6 +625,15 @@ QProgressBar::chunk#thrustBar { + + + + 255 + 255 + 255 + + + @@ -435,6 +661,42 @@ QProgressBar::chunk#thrustBar { + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc index 25b7171..ee99801 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); + + } + } } } @@ -498,13 +522,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) +void WaypointList::setIsWPGlobal(bool value, QPointF centerCoordinate) { + centerMapCoordinate = centerCoordinate; if(isLocalWP) diff --git a/src/ui/WaypointList.h b/src/ui/WaypointList.h index b4d2593..6bc1807 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 @@ -105,6 +105,7 @@ public slots: signals: void clearPathclicked(); + void createWaypointAtMap(const QPointF coordinate); @@ -122,6 +123,7 @@ protected: double mavYaw; bool isGlobalWP; bool isLocalWP; + QPointF centerMapCoordinate; private: Ui::WaypointList *m_ui; From 7c6cb93651fc326bec0682c9917b7837cf60fd29 Mon Sep 17 00:00:00 2001 From: tecnosapiens Date: Fri, 17 Sep 2010 17:12:50 -0500 Subject: [PATCH 2/6] add new Widget for global waypoint whit functionalities for edition of waypoints created --- lib/QMapControl/src/layer.cpp | 32 ++ lib/QMapControl/src/layer.h | 6 + src/ui/MainWindow.cc | 2 + src/ui/MapWidget.cc | 32 +- src/ui/MapWidget.h | 3 + src/ui/WaypointGlobalView.cpp | 267 +++++++++- src/ui/WaypointGlobalView.h | 16 + src/ui/WaypointGlobalView.ui | 1170 +++++++++++++++++++++++------------------ src/ui/WaypointList.cc | 30 +- src/ui/WaypointList.h | 4 + 10 files changed, 1047 insertions(+), 515 deletions(-) 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/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index db61db3..7be5340 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -109,6 +109,8 @@ MainWindow::MainWindow(QWidget *parent) : // it notifies that a waypoint global goes to do create and a map graphic too connect(waypoints, SIGNAL(createWaypointAtMap(QPointF)), map, SLOT(createWaypointGraphAtMap(QPointF))); + // it notifies that a waypoint global change it´s position by spinBox on Widget WaypointView + connect(waypoints, SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), map, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float))); } MainWindow::~MainWindow() diff --git a/src/ui/MapWidget.cc b/src/ui/MapWidget.cc index 0804170..eac3404 100644 --- a/src/ui/MapWidget.cc +++ b/src/ui/MapWidget.cc @@ -49,6 +49,8 @@ MapWidget::MapWidget(QWidget *parent) : { m_ui->setupUi(this); + waypointIsDrag = false; + // Accept focus by clicking or keyboard this->setFocusPolicy(Qt::StrongFocus); @@ -397,6 +399,8 @@ void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){ Q_UNUSED(coordinate); + waypointIsDrag = true; + // Refresh the screen mc->updateRequestNew(); @@ -418,6 +422,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){ void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate) { + waypointIsDrag = false; mc->setMouseMode(qmapcontrol::MapControl::Panning); @@ -597,10 +602,35 @@ void MapWidget::clearPath() wpIndex.clear(); mc->updateRequestNew(); - // si el boton de crear wp globales esta activo desactivarlo llamando a su evento clicket + // si el boton de crear wp globales esta activo desactivarlo llamando a su evento clicked 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 6adf3f2..9654af3 100644 --- a/src/ui/MapWidget.h +++ b/src/ui/MapWidget.h @@ -65,6 +65,7 @@ public slots: //ROCA void clearPath(); + void changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon); protected: void changeEvent(QEvent* e); @@ -114,6 +115,7 @@ protected: + signals: //void movePoint(QPointF newCoord); void captureMapCoordinateClick(const QPointF coordinate); //ROCA @@ -127,6 +129,7 @@ private: QHash wpIndex; LineString* path; QPen* pointPen; + bool waypointIsDrag; }; #endif // MAPWIDGET_H diff --git a/src/ui/WaypointGlobalView.cpp b/src/ui/WaypointGlobalView.cpp index b57df7f..50cdeab 100644 --- a/src/ui/WaypointGlobalView.cpp +++ b/src/ui/WaypointGlobalView.cpp @@ -12,14 +12,29 @@ WaypointGlobalView::WaypointGlobalView(Waypoint* wp,QWidget *parent) : 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))); + + //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))); + + + + // latitude spinBox + + 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))); @@ -48,9 +63,50 @@ WaypointGlobalView::~WaypointGlobalView() 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()));\ +// ui->m_latitudtextEdit->setText(getLatitudString(wp->getY())); + +// ui->m_longitudtextEdit->setText(getLongitudString(wp->getX())); + + 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); + + } + + + 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())); } @@ -152,4 +208,205 @@ void WaypointGlobalView::changeOrbitalState(int state) } } +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); + +} + + diff --git a/src/ui/WaypointGlobalView.h b/src/ui/WaypointGlobalView.h index 293b8b1..93c20a2 100644 --- a/src/ui/WaypointGlobalView.h +++ b/src/ui/WaypointGlobalView.h @@ -22,12 +22,28 @@ 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); + + //update longitude + void updateLongitudeWP(int value); + void updateLongitudeMinuteWP(double value); + 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 85ffd0b..06a9ceb 100644 --- a/src/ui/WaypointGlobalView.ui +++ b/src/ui/WaypointGlobalView.ui @@ -6,8 +6,8 @@ 0 0 - 940 - 56 + 824 + 72 @@ -143,7 +143,7 @@ QProgressBar::chunk#thrustBar { background-color: orange; } - + 0 @@ -161,555 +161,713 @@ QProgressBar::chunk#thrustBar { - - + + + + + 10 + 75 + true + + WP_id - + Qt::Horizontal - 10 - 13 + 16 + 20 - - - - Lat: + + + + + 75 + true + - - - - - - - 0 - 0 - + + - - - 120 - 25 - - - - Qt::ScrollBarAlwaysOff + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - + true + + + + + + 10 + 75 + true + + + + LAT: + + + + + + + 0 + + + 89 + + + + + + + + 16 + 75 + true + + + + ° + + + + + + + 0.000000000000000 + + + 59.990000000000002 + + + 0.010000000000000 + + + + + + + + 14 + 75 + true + + + + ´ + + + + + + + N + + + true + + + + + + + S + + + + - - - - Qt::Horizontal - - - - 50 - 30 - - - - - - - - Lon: - - - - - - - - 120 - 25 - - - - Qt::ScrollBarAlwaysOff - - - true - - - - + Qt::Horizontal - 50 - 30 + 11 + 20 - - - - Heigth + + + + + 75 + true + + + + + + + + + + 10 + 75 + true + + + + LON: + + + + + + + -179 + + + 179 + + + + + + + + 16 + 75 + true + + + + ° + + + + + + + 0.000000000000000 + + + 59.990000000000002 + + + 0.010000000000000 + + + + + + + + 16 + 75 + true + + + + ´ + + + + + + + W + + + true + + + + + + + E + + + + - - - - - + + Qt::Horizontal - 86 - 13 + 16 + 20 - - - - - - - - - 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 - - - - - - - - Orbital - - - - - - - true + + + + + + + + + Heigth + + + + + + + + + + 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 ee99801..f1e52c0 100644 --- a/src/ui/WaypointList.cc +++ b/src/ui/WaypointList.cc @@ -325,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))); } @@ -547,10 +549,13 @@ void WaypointList::setIsWPGlobal(bool value, QPointF centerCoordinate) if(ret) { clearLocalWPWidget(); - isGlobalWP = value; - isLocalWP = !(value); + + } + } + isLocalWP = !value; + isGlobalWP = value; } @@ -583,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) @@ -598,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 6bc1807..2432504 100644 --- a/src/ui/WaypointList.h +++ b/src/ui/WaypointList.h @@ -95,6 +95,8 @@ public slots: void clearLocalWPWidget(); + void changeWPPositionBySpinBox(Waypoint* wp); + // Waypoint operations void moveUp(Waypoint* wp); void moveDown(Waypoint* wp); @@ -106,6 +108,8 @@ public slots: signals: void clearPathclicked(); void createWaypointAtMap(const QPointF coordinate); + // void ChangeWaypointGlobalPosition(int index, QPointF coord); + void changePositionWPGlobalBySpinBox(int indexWP, float lat, float lon); From 7cb3cbff1b46f720ff8061d28755a93025b3e567 Mon Sep 17 00:00:00 2001 From: Mariano Lizarraga Date: Sat, 18 Sep 2010 13:13:13 -0500 Subject: [PATCH 3/6] Minor changes to account for new XML file for SLUGS --- src/uas/SlugsMAV.cc | 2 +- src/ui/WaypointList.cc | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/uas/SlugsMAV.cc b/src/uas/SlugsMAV.cc index f053345..443516d 100644 --- a/src/uas/SlugsMAV.cc +++ b/src/uas/SlugsMAV.cc @@ -30,7 +30,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/WaypointList.cc b/src/ui/WaypointList.cc index 25b7171..17e29e1 100644 --- a/src/ui/WaypointList.cc +++ b/src/ui/WaypointList.cc @@ -512,8 +512,8 @@ 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); From 92da66d96fcd307e8535b4b9a1f750d85c8e64e5 Mon Sep 17 00:00:00 2001 From: tecnosapiens Date: Sat, 18 Sep 2010 14:11:43 -0500 Subject: [PATCH 4/6] add functionalities for change direction of Latitude and Longitude in WaypointGlobalView.h when user editing it --- src/Waypoint.h | 1 + src/WaypointGlobal.cpp | 10 ---------- src/WaypointGlobal.h | 29 ----------------------------- src/ui/MapWidget.cc | 2 +- 4 files changed, 2 insertions(+), 40 deletions(-) delete mode 100644 src/WaypointGlobal.cpp delete mode 100644 src/WaypointGlobal.h 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/ui/MapWidget.cc b/src/ui/MapWidget.cc index eac3404..5e1af48 100644 --- a/src/ui/MapWidget.cc +++ b/src/ui/MapWidget.cc @@ -602,7 +602,7 @@ void MapWidget::clearPath() wpIndex.clear(); mc->updateRequestNew(); - // si el boton de crear wp globales esta activo desactivarlo llamando a su evento clicked + if(createPath->isChecked()) { createPath->click(); From 0ee8d15f36f2d5e3166bee370bb93a21c80f6d76 Mon Sep 17 00:00:00 2001 From: tecnosapiens Date: Sat, 18 Sep 2010 14:19:31 -0500 Subject: [PATCH 5/6] add functionalities for change direction of Latitude and Longitude in Waypoint.h when user editing it --- src/ui/WaypointGlobalView.cpp | 142 ++++++++++++++++++++++++++++-------------- src/ui/WaypointGlobalView.h | 2 + 2 files changed, 98 insertions(+), 46 deletions(-) diff --git a/src/ui/WaypointGlobalView.cpp b/src/ui/WaypointGlobalView.cpp index 50cdeab..44a9202 100644 --- a/src/ui/WaypointGlobalView.cpp +++ b/src/ui/WaypointGlobalView.cpp @@ -21,17 +21,18 @@ WaypointGlobalView::WaypointGlobalView(Waypoint* wp,QWidget *parent) : //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())); - // latitude spinBox - - - connect(ui->m_orbitCheckBox, SIGNAL(stateChanged(int)), this, SLOT(changeOrbitalState(int))); + connect(ui->m_orbitCheckBox, SIGNAL(stateChanged(int)), this, SLOT(changeOrbitalState(int))); @@ -63,51 +64,47 @@ WaypointGlobalView::~WaypointGlobalView() void WaypointGlobalView::updateValues() { -// ui->m_latitudtextEdit->setText(getLatitudString(wp->getY())); - -// ui->m_longitudtextEdit->setText(getLongitudString(wp->getX())); - - 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); - } + 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())); - 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) @@ -408,5 +405,58 @@ void WaypointGlobalView::updateLongitudeMinuteWP(double value) } +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.h b/src/ui/WaypointGlobalView.h index 93c20a2..02fc795 100644 --- a/src/ui/WaypointGlobalView.h +++ b/src/ui/WaypointGlobalView.h @@ -32,10 +32,12 @@ public slots: //update latitude void updateLatitudeWP(int value); void updateLatitudeMinuteWP(double value); + void changeDirectionLatitudeWP(); //update longitude void updateLongitudeWP(int value); void updateLongitudeMinuteWP(double value); + void changeDirectionLongitudeWP(); From 891351daf536e544857e7b8f3936f75b402a96dd Mon Sep 17 00:00:00 2001 From: tecnosapiens Date: Sat, 18 Sep 2010 14:24:22 -0500 Subject: [PATCH 6/6] modify by delete of non necessary own class --- qgroundcontrol.pro | 2 -- 1 file changed, 2 deletions(-) diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 383f998..510504b 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -157,7 +157,6 @@ HEADERS += src/MG.h \ src/ui/map/Waypoint2DIcon.h \ src/ui/map/MAV2DIcon.h \ src/ui/map/QGC2DIcon.h \ - src/WaypointGlobal.h \ src/ui/WaypointGlobalView.h SOURCES += src/main.cc \ src/Core.cc \ @@ -222,7 +221,6 @@ SOURCES += src/main.cc \ src/ui/map/Waypoint2DIcon.cc \ src/ui/map/MAV2DIcon.cc \ src/ui/map/QGC2DIcon.cc \ - src/WaypointGlobal.cpp \ src/ui/WaypointGlobalView.cpp RESOURCES = mavground.qrc