From e605f2dccfaf299f205d2c9f2dad9cc9a2192153 Mon Sep 17 00:00:00 2001 From: tecnosapiens Date: Mon, 13 Sep 2010 14:49:54 -0500 Subject: [PATCH] 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;