diff --git a/src/Airmap/AirMapFlightManager.cc b/src/Airmap/AirMapFlightManager.cc index 72ac56c05bd880b379e59004ca2ae179da89463f..d85c0dab209794a198d38685c3aa4d15d9fc4be4 100644 --- a/src/Airmap/AirMapFlightManager.cc +++ b/src/Airmap/AirMapFlightManager.cc @@ -34,46 +34,52 @@ void AirMapFlightManager::findFlight(const QGCGeoBoundingCube& bc) { _state = State::FetchFlights; - Flights::Search::Parameters params; - QList coords = bc.polygon2D(); - Geometry::LineString lineString; - for (const auto& qcoord : coords) { - Geometry::Coordinate coord; - coord.latitude = qcoord.latitude(); - coord.longitude = qcoord.longitude(); - lineString.coordinates.push_back(coord); - } - _flightID.clear(); - params.geometry = Geometry(lineString); + _searchArea = bc; std::weak_ptr isAlive(_instance); - _shared.client()->flights().search(params, [this, isAlive, bc](const Flights::Search::Result& result) { + _shared.doRequestWithLogin([this, isAlive](const QString& login_token) { if (!isAlive.lock()) return; if (_state != State::FetchFlights) return; - if (result && result.value().flights.size() > 0) { - const Flights::Search::Response& response = result.value(); - qCDebug(AirMapManagerLog) << "Find flights response"; - for (const auto& flight : response.flights) { - QString fid = QString::fromStdString(flight.id); - qCDebug(AirMapManagerLog) << "Checking flight:" << fid; - if(flight.geometry.type() == Geometry::Type::line_string) { - const Geometry::LineString& lineString = flight.geometry.details_for_line_string(); - QList rcoords; - for (const auto& vertex : lineString.coordinates) { - rcoords.append(QGeoCoordinate(vertex.latitude, vertex.longitude)); - } - if(bc == rcoords) { - qCDebug(AirMapManagerLog) << "Found match:" << fid; - _flightID = fid; - emit flightIDChanged(); - return; + QList coords = _searchArea.polygon2D(); + Geometry::LineString lineString; + for (const auto& qcoord : coords) { + Geometry::Coordinate coord; + coord.latitude = qcoord.latitude(); + coord.longitude = qcoord.longitude(); + lineString.coordinates.push_back(coord); + } + _flightID.clear(); + Flights::Search::Parameters params; + params.authorization = login_token.toStdString(); + params.geometry = Geometry(lineString); + _shared.client()->flights().search(params, [this, isAlive](const Flights::Search::Result& result) { + if (!isAlive.lock()) return; + if (_state != State::FetchFlights) return; + if (result && result.value().flights.size() > 0) { + const Flights::Search::Response& response = result.value(); + qCDebug(AirMapManagerLog) << "Find flights response"; + for (const auto& flight : response.flights) { + QString fid = QString::fromStdString(flight.id); + qCDebug(AirMapManagerLog) << "Checking flight:" << fid; + if(flight.geometry.type() == Geometry::Type::line_string) { + const Geometry::LineString& lineString = flight.geometry.details_for_line_string(); + QList rcoords; + for (const auto& vertex : lineString.coordinates) { + rcoords.append(QGeoCoordinate(vertex.latitude, vertex.longitude)); + } + if(_searchArea == rcoords) { + qCDebug(AirMapManagerLog) << "Found match:" << fid; + _flightID = fid; + _state = State::Idle; + emit flightIDChanged(); + return; + } } } } - } else { - _state = State::Idle; - } - qCDebug(AirMapManagerLog) << "No flights found"; - emit flightIDChanged(); + qCDebug(AirMapManagerLog) << "No flights found"; + emit flightIDChanged(); + }); + _state = State::Idle; }); } diff --git a/src/Airmap/AirMapFlightManager.h b/src/Airmap/AirMapFlightManager.h index e1286831df2c2f931fe8e834a4600703bc2a8dc8..e34725f3356ba57225e3a8fb85566cc61dd6e097 100644 --- a/src/Airmap/AirMapFlightManager.h +++ b/src/Airmap/AirMapFlightManager.h @@ -13,8 +13,8 @@ #include "AirMapSharedState.h" #include "AirspaceFlightPlanProvider.h" -#include #include +#include #include #include @@ -33,8 +33,8 @@ public: QString flightID () { return _flightID; } signals: - void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails); - void flightIDChanged (); + void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails); + void flightIDChanged (); private: @@ -49,5 +49,6 @@ private: AirMapSharedState& _shared; QString _flightID; QString _pilotID; ///< Pilot ID in the form "auth0|abc123" + QGCGeoBoundingCube _searchArea; }; diff --git a/src/Airmap/AirMapFlightPlanManager.cc b/src/Airmap/AirMapFlightPlanManager.cc index bc854cde4d6fcd85db2f45acb70dba3fea4407a5..205687953b984effd103ec5b17559af3ed130167 100644 --- a/src/Airmap/AirMapFlightPlanManager.cc +++ b/src/Airmap/AirMapFlightPlanManager.cc @@ -25,6 +25,16 @@ using namespace airmap; +//----------------------------------------------------------------------------- +AirMapFlightInfo::AirMapFlightInfo(const airmap::Flight& flight, QObject *parent) + : AirspaceFlightInfo(parent) +{ + _flight = flight; + //-- TODO: Load bounding box geometry + + +} + //----------------------------------------------------------------------------- AirMapFlightPlanManager::AirMapFlightPlanManager(AirMapSharedState& shared, QObject *parent) : AirspaceFlightPlanProvider(parent) @@ -108,6 +118,7 @@ AirMapFlightPlanManager::submitFlightPlan() qCWarning(AirMapManagerLog) << "Submit flight with no flight plan."; return; } + _flightId.clear(); _state = State::FlightSubmit; FlightPlans::Submit::Parameters params; params.authorization = _shared.loginToken().toStdString(); @@ -125,6 +136,8 @@ AirMapFlightPlanManager::submitFlightPlan() emit error("Failed to submit Flight Plan", QString::fromStdString(result.error().message()), description); _state = State::Idle; + _flightPermitStatus = AirspaceFlightPlanProvider::PermitRejected; + emit flightPermitStatusChanged(); } }); } @@ -318,7 +331,7 @@ AirMapFlightPlanManager::_uploadFlightPlan() } else { _state = State::Idle; QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : ""); - emit error("Flight Plan update failed", QString::fromStdString(result.error().message()), description); + emit error("Flight Plan creation failed", QString::fromStdString(result.error().message()), description); } }); }); @@ -396,7 +409,7 @@ AirMapFlightPlanManager::_updateFlightPlan() } else { _state = State::Idle; QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : ""); - emit error("Flight Plan creation failed", QString::fromStdString(result.error().message()), description); + emit error("Flight Plan update failed", QString::fromStdString(result.error().message()), description); } }); }); @@ -605,3 +618,75 @@ AirMapFlightPlanManager::_missionChanged() } } } + +//----------------------------------------------------------------------------- +void +AirMapFlightPlanManager::loadFlightList() +{ + qCDebug(AirMapManagerLog) << "Search flights"; + if (_pilotID == "") { + //-- Need to get the pilot id + qCDebug(AirMapManagerLog) << "Getting pilot ID"; + _state = State::GetPilotID; + std::weak_ptr isAlive(_instance); + _shared.doRequestWithLogin([this, isAlive](const QString& login_token) { + if (!isAlive.lock()) return; + Pilots::Authenticated::Parameters params; + params.authorization = login_token.toStdString(); + _shared.client()->pilots().authenticated(params, [this, isAlive](const Pilots::Authenticated::Result& result) { + if (!isAlive.lock()) return; + if (_state != State::GetPilotID) return; + if (result) { + _pilotID = QString::fromStdString(result.value().id); + qCDebug(AirMapManagerLog) << "Got Pilot ID:"<<_pilotID; + _state = State::Idle; + _loadFlightList(); + } else { + _state = State::Idle; + QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : ""); + emit error("Failed to get pilot ID", QString::fromStdString(result.error().message()), description); + return; + } + }); + }); + } else { + _loadFlightList(); + } +} + +//----------------------------------------------------------------------------- +void +AirMapFlightPlanManager::_loadFlightList() +{ + _flightList.clearAndDeleteContents(); + emit flightListChanged(); + _state = State::LoadFlightList; + std::weak_ptr isAlive(_instance); + _shared.doRequestWithLogin([this, isAlive](const QString& login_token) { + if (!isAlive.lock()) return; + if (_state != State::LoadFlightList) return; + Flights::Search::Parameters params; + params.authorization = login_token.toStdString(); + params.limit = 200; + params.pilot_id = _pilotID.toStdString(); + _shared.client()->flights().search(params, [this, isAlive](const Flights::Search::Result& result) { + if (!isAlive.lock()) return; + if (_state != State::LoadFlightList) return; + if (result && result.value().flights.size() > 0) { + const Flights::Search::Response& response = result.value(); + for (const auto& flight : response.flights) { + AirMapFlightInfo* pFlight = new AirMapFlightInfo(flight, this); + _flightList.append(pFlight); + qCDebug(AirMapManagerLog) << "Found:" << pFlight->flightID(); + } + emit flightListChanged(); + } else { + if(!result) { + QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : ""); + emit error("Flight search failed", QString::fromStdString(result.error().message()), description); + } + } + }); + }); +} + diff --git a/src/Airmap/AirMapFlightPlanManager.h b/src/Airmap/AirMapFlightPlanManager.h index 74ca5da8876c5e77c686c2a2fd0563bd55928c04..e0b1df63277d51e79bd5eb501e53602b29200560 100644 --- a/src/Airmap/AirMapFlightPlanManager.h +++ b/src/Airmap/AirMapFlightPlanManager.h @@ -18,8 +18,27 @@ #include #include +#include "airmap/flight.h" + class PlanMasterController; +//----------------------------------------------------------------------------- +class AirMapFlightInfo : public AirspaceFlightInfo +{ + Q_OBJECT +public: + AirMapFlightInfo (const airmap::Flight& flight, QObject *parent = nullptr); + virtual QString flightID () override { return QString::fromStdString(_flight.id); } + virtual QDateTime createdTime () override { return QDateTime(); } //-- TODO: Need to get rid of boost first + virtual QDateTime startTime () override { return QDateTime(); } //-- TODO: Need to get rid of boost first + virtual QDateTime endTime () override { return QDateTime(); } //-- TODO: Need to get rid of boost first + virtual QGeoCoordinate takeOff () override { return QGeoCoordinate(_flight.latitude, _flight.longitude);} + virtual QmlObjectListModel* boundingBox () override { return &_boundingBox; } +private: + airmap::Flight _flight; + QmlObjectListModel _boundingBox; +}; + //----------------------------------------------------------------------------- /// class to upload a flight class AirMapFlightPlanManager : public AirspaceFlightPlanProvider, public LifetimeChecker @@ -45,12 +64,14 @@ public: QmlObjectListModel* rulesReview () override { return &_rulesReview; } QmlObjectListModel* rulesFollowing () override { return &_rulesFollowing; } QmlObjectListModel* briefFeatures () override { return &_briefFeatures; } + QmlObjectListModel* flightList () override { return &_flightList; } void updateFlightPlan () override; + void submitFlightPlan () override; void startFlightPlanning (PlanMasterController* planController) override; void setFlightStartTime (QDateTime start) override; void setFlightEndTime (QDateTime end) override; - void submitFlightPlan () override; + void loadFlightList () override; signals: void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails); @@ -65,6 +86,7 @@ private: void _createFlightPlan (); void _deleteFlightPlan (); bool _collectFlightDtata (); + void _loadFlightList (); private: enum class State { @@ -76,6 +98,7 @@ private: FlightDelete, FlightSubmit, FlightPolling, + LoadFlightList, }; struct Flight { @@ -108,6 +131,7 @@ private: QmlObjectListModel _rulesReview; QmlObjectListModel _rulesFollowing; QmlObjectListModel _briefFeatures; + QmlObjectListModel _flightList; AirspaceAdvisoryProvider::AdvisoryColor _airspaceColor; AirspaceFlightPlanProvider::PermitStatus _flightPermitStatus = AirspaceFlightPlanProvider::PermitNone; diff --git a/src/Airmap/AirMapManager.cc b/src/Airmap/AirMapManager.cc index 9020d99f241cc57018d42698e6f606ded2468fab..a623fcd35551affc5aabd6ac4fcbefc96c3a7466 100644 --- a/src/Airmap/AirMapManager.cc +++ b/src/Airmap/AirMapManager.cc @@ -37,8 +37,8 @@ AirMapManager::AirMapManager(QGCApplication* app, QGCToolbox* toolbox) { _logger = std::make_shared(); qt::register_types(); // TODO: still needed? - _logger->logging_category().setEnabled(QtDebugMsg, true); - _logger->logging_category().setEnabled(QtInfoMsg, true); + _logger->logging_category().setEnabled(QtDebugMsg, false); + _logger->logging_category().setEnabled(QtInfoMsg, false); _logger->logging_category().setEnabled(QtWarningMsg, true); _dispatchingLogger = std::make_shared(_logger); connect(&_shared, &AirMapSharedState::error, this, &AirMapManager::_error); diff --git a/src/Airmap/AirMapVehicleManager.cc b/src/Airmap/AirMapVehicleManager.cc index bd3a2d0c39d435b9ccfa84eef86d98d9a750485c..4fa62af14f6b133166fcca7721161c04ba7831be 100644 --- a/src/Airmap/AirMapVehicleManager.cc +++ b/src/Airmap/AirMapVehicleManager.cc @@ -31,6 +31,7 @@ void AirMapVehicleManager::startTelemetryStream() { if (!_flightManager.flightID().isEmpty()) { + //-- TODO: This will start telemetry using the current flight ID in memory _telemetry.startTelemetryStream(_flightManager.flightID()); } } diff --git a/src/Airmap/AirmapSettings.qml b/src/Airmap/AirmapSettings.qml index 29e1e839a52b70c7d5493991a8ef731d123f0d05..8ac4c2f4dbc6a77788ff59a824703ea91f31f0c6 100644 --- a/src/Airmap/AirmapSettings.qml +++ b/src/Airmap/AirmapSettings.qml @@ -229,6 +229,46 @@ QGCView { FactTextField { fact: QGroundControl.settingsManager.airMapSettings.password; echoMode: TextInput.Password } } } + //----------------------------------------------------------------- + //-- Flight List + Item { + width: _panelWidth + height: flightListLabel.height + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.horizontalCenter: parent.horizontalCenter + visible: QGroundControl.settingsManager.appSettings.visible + QGCLabel { + id: flightListLabel + text: qsTr("Flight List") + font.family: ScreenTools.demiboldFontFamily + } + Component.onCompleted: { + QGroundControl.airspaceManager.flightPlan.loadFlightList() + } + } + Rectangle { + height: flightCol.height + (ScreenTools.defaultFontPixelHeight * 2) + width: _panelWidth + color: qgcPal.windowShade + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.horizontalCenter: parent.horizontalCenter + Column { + id: flightCol + spacing: ScreenTools.defaultFontPixelHeight + anchors.centerIn: parent + Repeater { + model: QGroundControl.airspaceManager.flightPlan.flightList + Row { + spacing: ScreenTools.defaultFontPixelWidth + QGCCheckBox { + text: object.flightID + checked: object.selected + onClicked: object.selected = checked + } + } + } + } + } } } } diff --git a/src/Airmap/FlightBrief.qml b/src/Airmap/FlightBrief.qml index b6e47bb22c5ea0eb7a8f367c5f1466653682bb3f..6cf7b94cdbb1f5147a1e533c5571c26bff742661 100644 --- a/src/Airmap/FlightBrief.qml +++ b/src/Airmap/FlightBrief.qml @@ -179,7 +179,7 @@ Item { width: ScreenTools.defaultFontPixelWidth * 12 visible: planView onClicked: { - //-- TODO: File Plan + QGroundControl.airspaceManager.flightPlan.submitFlightPlan() mainWindow.enableToolbar() rootLoader.sourceComponent = null } diff --git a/src/AirspaceManagement/AirspaceFlightPlanProvider.cc b/src/AirspaceManagement/AirspaceFlightPlanProvider.cc index 888e9d0c347c36691128fe5368a5b34550c48c11..463949c114e7401b780c5f62bf149280419e1dbd 100644 --- a/src/AirspaceManagement/AirspaceFlightPlanProvider.cc +++ b/src/AirspaceManagement/AirspaceFlightPlanProvider.cc @@ -9,6 +9,12 @@ #include "AirspaceFlightPlanProvider.h" +AirspaceFlightInfo::AirspaceFlightInfo(QObject *parent) + : QObject(parent) + , _selected(false) +{ +} + AirspaceFlightPlanProvider::AirspaceFlightPlanProvider(QObject *parent) : QObject(parent) { diff --git a/src/AirspaceManagement/AirspaceFlightPlanProvider.h b/src/AirspaceManagement/AirspaceFlightPlanProvider.h index 4a2a73250b1cbc4fc988809d9a640512be7c6585..6fa119c29425c7136325b6522db6788d508ed8c5 100644 --- a/src/AirspaceManagement/AirspaceFlightPlanProvider.h +++ b/src/AirspaceManagement/AirspaceFlightPlanProvider.h @@ -22,6 +22,38 @@ class PlanMasterController; +//----------------------------------------------------------------------------- +class AirspaceFlightInfo : public QObject +{ + Q_OBJECT +public: + AirspaceFlightInfo (QObject *parent = nullptr); + + Q_PROPERTY(QString flightID READ flightID CONSTANT) + Q_PROPERTY(QDateTime createdTime READ createdTime CONSTANT) + Q_PROPERTY(QDateTime startTime READ startTime CONSTANT) + Q_PROPERTY(QDateTime endTime READ endTime CONSTANT) + Q_PROPERTY(QGeoCoordinate takeOff READ takeOff CONSTANT) + Q_PROPERTY(QmlObjectListModel* boundingBox READ boundingBox CONSTANT) + Q_PROPERTY(bool selected READ selected WRITE setSelected NOTIFY selectedChanged) + + virtual QString flightID () = 0; + virtual QDateTime createdTime () = 0; + virtual QDateTime startTime () = 0; + virtual QDateTime endTime () = 0; + virtual QGeoCoordinate takeOff () = 0; + virtual QmlObjectListModel* boundingBox () = 0; + + virtual bool selected () { return _selected; } + virtual void setSelected (bool sel) { _selected = sel; emit selectedChanged(); } + +signals: + void selectedChanged (); + +protected: + bool _selected; +}; + //----------------------------------------------------------------------------- class AirspaceFlightPlanProvider : public QObject { @@ -38,7 +70,6 @@ public: Q_ENUM(PermitStatus) AirspaceFlightPlanProvider (QObject *parent = nullptr); - virtual ~AirspaceFlightPlanProvider () {} Q_PROPERTY(PermitStatus flightPermitStatus READ flightPermitStatus NOTIFY flightPermitStatusChanged) ///< State of flight permission Q_PROPERTY(QDateTime flightStartTime READ flightStartTime WRITE setFlightStartTime NOTIFY flightStartTimeChanged) ///< Start of flight @@ -54,8 +85,12 @@ public: Q_PROPERTY(QmlObjectListModel* rulesReview READ rulesReview NOTIFY rulesChanged) Q_PROPERTY(QmlObjectListModel* rulesFollowing READ rulesFollowing NOTIFY rulesChanged) Q_PROPERTY(QmlObjectListModel* briefFeatures READ briefFeatures NOTIFY rulesChanged) + Q_PROPERTY(QmlObjectListModel* flightList READ flightList NOTIFY flightListChanged) + //-- TODO: This will submit the current flight plan in memory. + Q_INVOKABLE virtual void submitFlightPlan () = 0; Q_INVOKABLE virtual void updateFlightPlan () = 0; + Q_INVOKABLE virtual void loadFlightList () = 0; virtual PermitStatus flightPermitStatus () const { return PermitNone; } virtual QDateTime flightStartTime () const = 0; @@ -71,12 +106,11 @@ public: virtual QmlObjectListModel* rulesReview () = 0; ///< List of AirspaceRule should review virtual QmlObjectListModel* rulesFollowing () = 0; ///< List of AirspaceRule following virtual QmlObjectListModel* briefFeatures () = 0; ///< List of AirspaceRule in violation + virtual QmlObjectListModel* flightList () = 0; ///< List of AirspaceFlightInfo virtual void setFlightStartTime (QDateTime start) = 0; virtual void setFlightEndTime (QDateTime end) = 0; virtual void startFlightPlanning (PlanMasterController* planController) = 0; - //-- TODO: This will submit the current flight plan in memory. - virtual void submitFlightPlan () = 0; signals: void flightPermitStatusChanged (); @@ -85,4 +119,5 @@ signals: void advisoryChanged (); void missionAreaChanged (); void rulesChanged (); + void flightListChanged (); };