From 26fc0ce0d0edbc93dbe266468b1abd2c58cc58f5 Mon Sep 17 00:00:00 2001 From: pixhawk Date: Thu, 29 Sep 2011 15:59:02 +0200 Subject: [PATCH] Added "editable" keyword to the name of functions, that are relevant for view-edit separation. --- src/uas/UASWaypointManager.cc | 42 +++++++++++++++++------------- src/uas/UASWaypointManager.h | 11 ++++---- src/ui/WaypointList.cc | 14 +++++----- src/ui/WaypointList.h | 2 +- src/ui/map/QGCMapWidget.cc | 18 ++++++------- src/ui/map3D/Pixhawk3DWidget.cc | 2 +- src/ui/map3D/QGCGoogleEarthView.cc | 8 +++--- 7 files changed, 52 insertions(+), 45 deletions(-) diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc index 1508793cf..5896c7278 100644 --- a/src/uas/UASWaypointManager.cc +++ b/src/uas/UASWaypointManager.cc @@ -145,7 +145,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_ if(wp->seq == current_wp_id) { //// // qDebug() << "Got WP: " << wp->seq << wp->x << wp->y << wp->z << wp->param4 << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << "Frame:"<< (MAV_FRAME) wp->frame << "Command:" << (MAV_CMD) wp->command; Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param1, wp->param2, wp->param3, wp->param4, wp->autocontinue, wp->current, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command); - addWaypoint(lwp, false); + addWaypointEditable(lwp, false); if (wp->current == 1) currentWaypoint = lwp; //get next waypoint @@ -248,18 +248,24 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m } } -void UASWaypointManager::notifyOfChange(Waypoint* wp) +void UASWaypointManager::notifyOfChangeEditable(Waypoint* wp) { // // qDebug() << "WAYPOINT CHANGED: ID:" << wp->getId(); // If only one waypoint was changed, emit only WP signal if (wp != NULL) { - emit waypointChanged(uas.getUASID(), wp); + emit waypointEditableChanged(uas.getUASID(), wp); } else { - emit waypointListChanged(); - emit waypointListChanged(uas.getUASID()); + emit waypointEditableListChanged(); + emit waypointEditableListChanged(uas.getUASID()); } } +//void notifyOfChangeViewOnly(Waypoint* wp) +//{ + +//} + + int UASWaypointManager::setCurrentWaypoint(quint16 seq) { if (seq < waypoints.size()) { @@ -300,7 +306,7 @@ int UASWaypointManager::setCurrentWaypoint(quint16 seq) * @param enforceFirstActive Enforces that the first waypoint is set as active * @see createWaypoint() is more suitable for most use cases */ -void UASWaypointManager::addWaypoint(Waypoint *wp, bool enforceFirstActive) +void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActive) { if (wp) { @@ -311,10 +317,10 @@ void UASWaypointManager::addWaypoint(Waypoint *wp, bool enforceFirstActive) currentWaypoint = wp; } waypoints.insert(waypoints.size(), wp); - connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChange(Waypoint*))); + connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*))); - emit waypointListChanged(); - emit waypointListChanged(uas.getUASID()); + emit waypointEditableListChanged(); + emit waypointEditableListChanged(uas.getUASID()); } } @@ -331,10 +337,10 @@ Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive) currentWaypoint = wp; } waypoints.insert(waypoints.size(), wp); - connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChange(Waypoint*))); + connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*))); - emit waypointListChanged(); - emit waypointListChanged(uas.getUASID()); + emit waypointEditableListChanged(); + emit waypointEditableListChanged(uas.getUASID()); return wp; } @@ -352,8 +358,8 @@ int UASWaypointManager::removeWaypoint(quint16 seq) waypoints[i]->setId(i); } - emit waypointListChanged(); - emit waypointListChanged(uas.getUASID()); + emit waypointEditableListChanged(); + emit waypointEditableListChanged(uas.getUASID()); return 0; } return -1; @@ -379,8 +385,8 @@ void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq) } waypoints[new_seq] = t; - emit waypointListChanged(); - emit waypointListChanged(uas.getUASID()); + emit waypointEditableListChanged(); + emit waypointEditableListChanged(uas.getUASID()); } } @@ -445,8 +451,8 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile) file.close(); emit loadWPFile(); - emit waypointListChanged(); - emit waypointListChanged(uas.getUASID()); + emit waypointEditableListChanged(); + emit waypointEditableListChanged(uas.getUASID()); } void UASWaypointManager::clearWaypointList() diff --git a/src/uas/UASWaypointManager.h b/src/uas/UASWaypointManager.h index 32945f209..bbd3a944a 100644 --- a/src/uas/UASWaypointManager.h +++ b/src/uas/UASWaypointManager.h @@ -124,21 +124,22 @@ public slots: void timeout(); ///< Called by the timer if a response times out. Handles send retries. /** @name Waypoint list operations */ /*@{*/ - void addWaypoint(Waypoint *wp, bool enforceFirstActive=true); ///< adds a new waypoint to the end of the list and changes its sequence number accordingly + void addWaypointEditable(Waypoint *wp, bool enforceFirstActive=true); ///< adds a new waypoint to the end of the editable list and changes its sequence number accordingly Waypoint* createWaypoint(bool enforceFirstActive=true); ///< Creates a waypoint int removeWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage void moveWaypoint(quint16 cur_seq, quint16 new_seq); ///< locally move a waypoint from its current position cur_seq to a new position new_seq void saveWaypoints(const QString &saveFile); ///< saves the local waypoint list to saveFile void loadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile - void notifyOfChange(Waypoint* wp); ///< Notifies manager to changes to a waypoint + void notifyOfChangeEditable(Waypoint* wp); ///< Notifies manager to changes to an editable waypoint + //void notifyOfChangeViewOnly(Waypoint* wp); ///< Notifies manager to changes to a viewonly waypoint /*@}*/ void handleLocalPositionChanged(UASInterface* mav, double x, double y, double z, quint64 time); void handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double alt, quint64 time); signals: - void waypointListChanged(void); ///< emits signal that the waypoint list has been changed - void waypointListChanged(int uasid); ///< Emits signal that list has been changed - void waypointChanged(int uasid, Waypoint* wp); ///< emits signal that waypoint has been changed + void waypointEditableListChanged(void); ///< emits signal that the list of editable waypoints has been changed + void waypointEditableListChanged(int uasid); ///< emits signal that the list of editable waypoints has been changed + void waypointEditableChanged(int uasid, Waypoint* wp); ///< emits signal that a single editable waypoint has been changed void currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number void updateStatusString(const QString &); ///< emits the current status string void waypointDistanceChanged(double distance); ///< Distance to next waypoint changed (in meters) diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc index 8591b3ca3..fa3b7afb7 100644 --- a/src/ui/WaypointList.cc +++ b/src/ui/WaypointList.cc @@ -126,8 +126,8 @@ void WaypointList::setUAS(UASInterface* uas) connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64))); connect(uas->getWaypointManager(), SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &))); - connect(uas->getWaypointManager(), SIGNAL(waypointListChanged(void)), this, SLOT(waypointListChanged(void))); - connect(uas->getWaypointManager(), SIGNAL(waypointChanged(int,Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*))); + connect(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged(void)), this, SLOT(waypointEditableListChanged(void))); + connect(uas->getWaypointManager(), SIGNAL(waypointEditableChanged(int,Waypoint*)), this, SLOT(updateWaypointEditable(int,Waypoint*))); connect(uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16))); //connect(uas->getWaypointManager(),SIGNAL(loadWPFile()),this,SLOT(setIsLoadFileWP())); //connect(uas->getWaypointManager(),SIGNAL(readGlobalWPFromUAS(bool)),this,SLOT(setIsReadGlobalWP(bool))); @@ -180,7 +180,7 @@ void WaypointList::add() Waypoint *last = waypoints.at(waypoints.size()-1); wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getParam1(), last->getParam2(), last->getParam3(), last->getParam4(), last->getAutoContinue(), false, last->getFrame(), last->getAction()); - uas->getWaypointManager()->addWaypoint(wp); + uas->getWaypointManager()->addWaypointEditable(wp); } else { @@ -215,7 +215,7 @@ void WaypointList::addCurrentPositionWaypoint() } // Create global frame waypoint per default wp = new Waypoint(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitude(), 0, acceptanceRadiusGlobal, holdTime, yawGlobal, true, true, MAV_FRAME_GLOBAL_RELATIVE_ALT, MAV_CMD_NAV_WAYPOINT); - uas->getWaypointManager()->addWaypoint(wp); + uas->getWaypointManager()->addWaypointEditable(wp); updateStatusLabel(tr("Added GLOBAL, ALTITUDE OVER GROUND waypoint")); } else if (uas->localPositionKnown()) @@ -229,7 +229,7 @@ void WaypointList::addCurrentPositionWaypoint() } // Create local frame waypoint as second option wp = new Waypoint(0, uas->getLocalX(), uas->getLocalY(), uas->getLocalZ(), uas->getYaw(), acceptanceRadiusLocal, holdTime, 0.0, true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT); - uas->getWaypointManager()->addWaypoint(wp); + uas->getWaypointManager()->addWaypointEditable(wp); updateStatusLabel(tr("Added LOCAL (NED) waypoint")); } else @@ -285,7 +285,7 @@ void WaypointList::updateWaypoint(int uas, Waypoint* wp) wpv->updateValues(); } -void WaypointList::waypointListChanged() +void WaypointList::waypointEditableListChanged() { if (uas) { // Prevent updates to prevent visual flicker @@ -341,7 +341,7 @@ void WaypointList::waypointListChanged() } } -//void WaypointList::waypointListChanged() +//void WaypointList::waypointEditableListChanged() //{ // if (uas) // { diff --git a/src/ui/WaypointList.h b/src/ui/WaypointList.h index 85a2bc6bc..e5def0c8d 100644 --- a/src/ui/WaypointList.h +++ b/src/ui/WaypointList.h @@ -87,7 +87,7 @@ public slots: /** @brief The waypoint manager informs that one waypoint was changed */ void updateWaypoint(int uas, Waypoint* wp); /** @brief The waypoint manager informs that the waypoint list was changed */ - void waypointListChanged(void); + void waypointEditableListChanged(void); // /** @brief The MapWidget informs that a waypoint global was changed on the map */ // void waypointGlobalChanged(const QPointF coordinate, const int indexWP); diff --git a/src/ui/map/QGCMapWidget.cc b/src/ui/map/QGCMapWidget.cc index bfcb0da68..ed1b371c1 100644 --- a/src/ui/map/QGCMapWidget.cc +++ b/src/ui/map/QGCMapWidget.cc @@ -164,7 +164,7 @@ void QGCMapWidget::mouseDoubleClickEvent(QMouseEvent* event) wp->setLongitude(pos.Lng()); wp->setAltitude(0); // wp->blockSignals(false); - // currWPManager->notifyOfChange(wp); + // currWPManager->notifyOfChangeEditable(wp); } } OPMapWidget::mouseDoubleClickEvent(event); @@ -190,10 +190,10 @@ void QGCMapWidget::activeUASSet(UASInterface* uas) if (currWPManager) { // Disconnect the waypoint manager / data storage from the UI - disconnect(currWPManager, SIGNAL(waypointListChanged(int)), this, SLOT(updateWaypointList(int))); - disconnect(currWPManager, SIGNAL(waypointChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*))); - disconnect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypoint(Waypoint*))); - disconnect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChange(Waypoint*))); + disconnect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int))); + disconnect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*))); + disconnect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*))); + disconnect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*))); } if (uas) @@ -201,10 +201,10 @@ void QGCMapWidget::activeUASSet(UASInterface* uas) currWPManager = uas->getWaypointManager(); // Connect the waypoint manager / data storage to the UI - connect(currWPManager, SIGNAL(waypointListChanged(int)), this, SLOT(updateWaypointList(int))); - connect(currWPManager, SIGNAL(waypointChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*))); - connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypoint(Waypoint*))); - connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChange(Waypoint*))); + connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int))); + connect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*))); + connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*))); + connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*))); updateSelectedSystem(uas->getUASID()); followUAVID = uas->getUASID(); diff --git a/src/ui/map3D/Pixhawk3DWidget.cc b/src/ui/map3D/Pixhawk3DWidget.cc index 009e962cb..729abf89b 100644 --- a/src/ui/map3D/Pixhawk3DWidget.cc +++ b/src/ui/map3D/Pixhawk3DWidget.cc @@ -278,7 +278,7 @@ Pixhawk3DWidget::insertWaypoint(void) if (wp) { wp->setFrame(frame); - uas->getWaypointManager()->addWaypoint(wp); + uas->getWaypointManager()->addWaypointEditable(wp); } } } diff --git a/src/ui/map3D/QGCGoogleEarthView.cc b/src/ui/map3D/QGCGoogleEarthView.cc index 332fefbb1..a05dc0bb9 100644 --- a/src/ui/map3D/QGCGoogleEarthView.cc +++ b/src/ui/map3D/QGCGoogleEarthView.cc @@ -209,9 +209,9 @@ void QGCGoogleEarthView::addUAS(UASInterface* uas) connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); // Receive waypoint updates // Connect the waypoint manager / data storage to the UI - connect(uas->getWaypointManager(), SIGNAL(waypointListChanged(int)), this, SLOT(updateWaypointList(int))); - connect(uas->getWaypointManager(), SIGNAL(waypointChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*))); - //connect(this, SIGNAL(waypointCreated(Waypoint*)), uas->getWaypointManager(), SLOT(addWaypoint(Waypoint*))); + connect(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int))); + connect(uas->getWaypointManager(), SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*))); + //connect(this, SIGNAL(waypointCreated(Waypoint*)), uas->getWaypointManager(), SLOT(addWaypointEditable(Waypoint*))); // TODO Update waypoint list on UI changes here } @@ -722,7 +722,7 @@ void QGCGoogleEarthView::updateState() wp->setLatitude(latitude); wp->setLongitude(longitude); wp->setAltitude(altitude); - mav->getWaypointManager()->notifyOfChange(wp); + mav->getWaypointManager()->notifyOfChangeEditable(wp); } } } -- 2.22.0