Browse Source

Switch advisory API

Handle flight start/end time
Handle start/stop traffic monitor
Only start telemetry if enabled
Added a "Now" button for the flight start time
Collect advisories only when the rules change
QGC4.4
Gus Grubba 7 years ago
parent
commit
e67ba35dfe
  1. 64
      src/Airmap/AirMapAdvisoryManager.cc
  2. 2
      src/Airmap/AirMapAdvisoryManager.h
  3. 122
      src/Airmap/AirMapFlightPlanManager.cc
  4. 11
      src/Airmap/AirMapFlightPlanManager.h
  5. 6
      src/Airmap/AirMapManager.cc
  6. 2
      src/Airmap/AirMapRulesetsManager.cc
  7. 12
      src/Airmap/AirMapTelemetry.cc
  8. 6
      src/Airmap/AirMapTrafficMonitor.cc
  9. 26
      src/Airmap/AirMapVehicleManager.cc
  10. 7
      src/Airmap/AirMapVehicleManager.h
  11. 1
      src/Airmap/FlightBrief.qml
  12. 37
      src/Airmap/FlightDetails.qml
  13. 42
      src/AirspaceManagement/AirspaceManager.cc
  14. 7
      src/AirspaceManagement/AirspaceManager.h
  15. 7
      src/FlightDisplay/FlightDisplayViewMap.qml
  16. 3
      src/PlanView/PlanView.qml

64
src/Airmap/AirMapAdvisoryManager.cc

@ -9,12 +9,16 @@
#include "AirMapAdvisoryManager.h" #include "AirMapAdvisoryManager.h"
#include "AirspaceRestriction.h" #include "AirspaceRestriction.h"
#include "AirMapRulesetsManager.h"
#include "AirMapManager.h" #include "AirMapManager.h"
#include "QGCApplication.h"
#include <cmath> #include <cmath>
#include <QTimer> #include <QTimer>
#include <QDateTime>
#include "airmap/airspaces.h" #include "airmap/airspaces.h"
#include "airmap/advisory.h"
#define ADVISORY_UPDATE_DISTANCE 500 //-- 500m threshold for updates #define ADVISORY_UPDATE_DISTANCE 500 //-- 500m threshold for updates
@ -68,27 +72,53 @@ AirMapAdvisoryManager::_requestAdvisories()
} }
_valid = false; _valid = false;
_advisories.clearAndDeleteContents(); _advisories.clearAndDeleteContents();
Status::GetStatus::Parameters params; Advisory::Search::Parameters params;
params.longitude = static_cast<float>(_lastROI.center().longitude()); //-- Geometry
params.latitude = static_cast<float>(_lastROI.center().latitude()); Geometry::Polygon polygon;
params.types = Airspace::Type::all; for (const auto& qcoord : _lastROI.polygon2D()) {
params.weather = false; Geometry::Coordinate coord;
double diagonal = _lastROI.pointNW.distanceTo(_lastROI.pointSE); coord.latitude = qcoord.latitude();
params.buffer = static_cast<std::uint32_t>(std::fmax(std::fmin(diagonal, 10000.0), 500.0)); coord.longitude = qcoord.longitude();
params.flight_date_time = Clock::universal_time(); polygon.outer_ring.coordinates.push_back(coord);
}
params.geometry = Geometry(polygon);
//-- Rulesets
AirMapRulesetsManager* pRulesMgr = dynamic_cast<AirMapRulesetsManager*>(qgcApp()->toolbox()->airspaceManager()->ruleSets());
QString ruleIDs;
if(pRulesMgr) {
for(int rs = 0; rs < pRulesMgr->ruleSets()->count(); rs++) {
AirMapRuleSet* ruleSet = qobject_cast<AirMapRuleSet*>(pRulesMgr->ruleSets()->get(rs));
//-- If this ruleset is selected
if(ruleSet && ruleSet->selected()) {
ruleIDs = ruleIDs + ruleSet->id();
//-- Separate rules with commas
if(rs < pRulesMgr->ruleSets()->count() - 1) {
ruleIDs = ruleIDs + ",";
}
}
}
}
params.rulesets = ruleIDs.toStdString();
//-- Time
quint64 start = static_cast<quint64>(QDateTime::currentDateTimeUtc().toMSecsSinceEpoch());
quint64 end = start + 60 * 30 * 1000;
params.start = airmap::from_milliseconds_since_epoch(airmap::milliseconds(static_cast<qint64>(start)));
params.end = airmap::from_milliseconds_since_epoch(airmap::milliseconds(static_cast<qint64>(end)));
std::weak_ptr<LifetimeChecker> isAlive(_instance); std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.client()->status().get_status_by_point(params, [this, isAlive](const Status::GetStatus::Result& result) { _shared.client()->advisory().search(params, [this, isAlive](const Advisory::Search::Result& result) {
if (!isAlive.lock()) return; if (!isAlive.lock()) return;
if (result) { if (result) {
qCDebug(AirMapManagerLog) << "Successful advisory search. Items:" << result.value().advisories.size(); qCDebug(AirMapManagerLog) << "Successful advisory search. Items:" << result.value().size();
_airspaceColor = (AirspaceAdvisoryProvider::AdvisoryColor)(int)result.value().advisory_color; _airspaceColor = AirspaceAdvisoryProvider::Green;
const std::vector<Status::Advisory> advisories = result.value().advisories; for (const auto& advisory : result.value()) {
for (const auto& advisory : advisories) {
AirMapAdvisory* pAdvisory = new AirMapAdvisory(this); AirMapAdvisory* pAdvisory = new AirMapAdvisory(this);
pAdvisory->_id = QString::fromStdString(advisory.airspace.id()); pAdvisory->_id = QString::fromStdString(advisory.advisory.airspace.id());
pAdvisory->_name = QString::fromStdString(advisory.airspace.name()); pAdvisory->_name = QString::fromStdString(advisory.advisory.airspace.name());
pAdvisory->_type = (AirspaceAdvisory::AdvisoryType)(int)advisory.airspace.type(); pAdvisory->_type = static_cast<AirspaceAdvisory::AdvisoryType>(advisory.advisory.airspace.type());
pAdvisory->_color = (AirspaceAdvisoryProvider::AdvisoryColor)(int)advisory.color; pAdvisory->_color = static_cast<AirspaceAdvisoryProvider::AdvisoryColor>(advisory.color);
if(pAdvisory->_color > _airspaceColor) {
_airspaceColor = pAdvisory->_color;
}
_advisories.append(pAdvisory); _advisories.append(pAdvisory);
qCDebug(AirMapManagerLog) << "Adding advisory" << pAdvisory->name(); qCDebug(AirMapManagerLog) << "Adding advisory" << pAdvisory->name();
} }

2
src/Airmap/AirMapAdvisoryManager.h

@ -32,7 +32,7 @@ class AirMapAdvisory : public AirspaceAdvisory
friend class AirMapAdvisoryManager; friend class AirMapAdvisoryManager;
friend class AirMapFlightPlanManager; friend class AirMapFlightPlanManager;
public: public:
AirMapAdvisory (QObject* parent = NULL); AirMapAdvisory (QObject* parent = nullptr);
QString id () override { return _id; } QString id () override { return _id; }
QString name () override { return _name; } QString name () override { return _name; }
AdvisoryType type () override { return _type; } AdvisoryType type () override { return _type; }

122
src/Airmap/AirMapFlightPlanManager.cc

@ -76,28 +76,28 @@ AirMapFlightInfo::AirMapFlightInfo(const airmap::Flight& flight, QObject *parent
QString QString
AirMapFlightInfo::createdTime() AirMapFlightInfo::createdTime()
{ {
return QDateTime::fromMSecsSinceEpoch((quint64)airmap::milliseconds_since_epoch(_flight.created_at)).toString("yyyy MM dd - hh:mm:ss"); return QDateTime::fromMSecsSinceEpoch(static_cast<qint64>(airmap::milliseconds_since_epoch(_flight.created_at))).toString("yyyy MM dd - hh:mm:ss");
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QString QString
AirMapFlightInfo::startTime() AirMapFlightInfo::startTime()
{ {
return QDateTime::fromMSecsSinceEpoch((quint64)airmap::milliseconds_since_epoch(_flight.start_time)).toString("yyyy MM dd - hh:mm:ss"); return QDateTime::fromMSecsSinceEpoch(static_cast<qint64>(airmap::milliseconds_since_epoch(_flight.start_time))).toString("yyyy MM dd - hh:mm:ss");
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QDateTime QDateTime
AirMapFlightInfo::qStartTime() AirMapFlightInfo::qStartTime()
{ {
return QDateTime::fromMSecsSinceEpoch((quint64)airmap::milliseconds_since_epoch(_flight.start_time)); return QDateTime::fromMSecsSinceEpoch(static_cast<qint64>(airmap::milliseconds_since_epoch(_flight.start_time)));
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool bool
AirMapFlightInfo::active() AirMapFlightInfo::active()
{ {
QDateTime end = QDateTime::fromMSecsSinceEpoch((quint64)airmap::milliseconds_since_epoch(_flight.end_time)); QDateTime end = QDateTime::fromMSecsSinceEpoch(static_cast<qint64>(airmap::milliseconds_since_epoch(_flight.end_time)));
QDateTime now = QDateTime::currentDateTime(); QDateTime now = QDateTime::currentDateTime();
return end > now; return end > now;
} }
@ -114,7 +114,7 @@ AirMapFlightInfo::setEndFlight(DateTime end)
QString QString
AirMapFlightInfo::endTime() AirMapFlightInfo::endTime()
{ {
return QDateTime::fromMSecsSinceEpoch((quint64)airmap::milliseconds_since_epoch(_flight.end_time)).toString("yyyy MM dd - hh:mm:ss"); return QDateTime::fromMSecsSinceEpoch(static_cast<qint64>(airmap::milliseconds_since_epoch(_flight.end_time))).toString("yyyy MM dd - hh:mm:ss");
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
@ -123,6 +123,8 @@ AirMapFlightPlanManager::AirMapFlightPlanManager(AirMapSharedState& shared, QObj
, _shared(shared) , _shared(shared)
{ {
connect(&_pollTimer, &QTimer::timeout, this, &AirMapFlightPlanManager::_pollBriefing); connect(&_pollTimer, &QTimer::timeout, this, &AirMapFlightPlanManager::_pollBriefing);
_flightStartTime = QDateTime::currentDateTime().addSecs(60);
_flightEndTime = _flightStartTime.addSecs(30 * 60);
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
@ -136,30 +138,31 @@ AirMapFlightPlanManager::~AirMapFlightPlanManager()
void void
AirMapFlightPlanManager::setFlightStartTime(QDateTime start) AirMapFlightPlanManager::setFlightStartTime(QDateTime start)
{ {
quint64 startt = start.toUTC().toMSecsSinceEpoch();
if(_flightPlan.start_time != airmap::from_milliseconds_since_epoch(airmap::milliseconds((long long)startt))) {
//-- Can't start in the past
if(start < QDateTime::currentDateTime()) { if(start < QDateTime::currentDateTime()) {
start = QDateTime::currentDateTime().addSecs(5 * 60); start = QDateTime::currentDateTime().addSecs(60);
startt = start.toUTC().toMSecsSinceEpoch();
} }
_flightPlan.start_time = airmap::from_milliseconds_since_epoch(airmap::milliseconds((long long)startt)); if(_flightStartTime != start) {
_flightStartTime = start;
emit flightStartTimeChanged(); emit flightStartTimeChanged();
} }
//-- End has to be after start
if(_flightEndTime < _flightStartTime) {
_flightEndTime = _flightStartTime.addSecs(30 * 60);
emit flightEndTimeChanged();
}
qCDebug(AirMapManagerLog) << "Set time" << _flightStartTime << _flightEndTime;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
AirMapFlightPlanManager::setFlightEndTime(QDateTime end) AirMapFlightPlanManager::setFlightEndTime(QDateTime end)
{ {
quint64 endt = end.toUTC().toMSecsSinceEpoch();
if(_flightPlan.end_time != airmap::from_milliseconds_since_epoch(airmap::milliseconds((long long)endt))) {
//-- End has to be after start //-- End has to be after start
if(end < flightStartTime()) { if(end < _flightStartTime) {
end = flightStartTime().addSecs(30 * 60); end = _flightStartTime.addSecs(30 * 60);
endt = end.toUTC().toMSecsSinceEpoch();
} }
_flightPlan.end_time = airmap::from_milliseconds_since_epoch(airmap::milliseconds((long long)endt)); if(_flightEndTime != end) {
_flightEndTime = end;
emit flightEndTimeChanged(); emit flightEndTimeChanged();
} }
} }
@ -168,14 +171,14 @@ AirMapFlightPlanManager::setFlightEndTime(QDateTime end)
QDateTime QDateTime
AirMapFlightPlanManager::flightStartTime() const AirMapFlightPlanManager::flightStartTime() const
{ {
return QDateTime::fromMSecsSinceEpoch((quint64)airmap::milliseconds_since_epoch(_flightPlan.start_time)); return _flightStartTime;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QDateTime QDateTime
AirMapFlightPlanManager::flightEndTime() const AirMapFlightPlanManager::flightEndTime() const
{ {
return QDateTime::fromMSecsSinceEpoch((quint64)airmap::milliseconds_since_epoch(_flightPlan.end_time)); return _flightEndTime;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
@ -205,6 +208,8 @@ AirMapFlightPlanManager::startFlightPlanning(PlanMasterController *planControlle
//-- Get notified of mission changes //-- Get notified of mission changes
connect(planController->missionController(), &MissionController::missionBoundingCubeChanged, this, &AirMapFlightPlanManager::_missionChanged); connect(planController->missionController(), &MissionController::missionBoundingCubeChanged, this, &AirMapFlightPlanManager::_missionChanged);
} }
//-- Set initial flight start time
setFlightStartTime(QDateTime::currentDateTime().addSecs(5 * 60));
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
@ -216,6 +221,7 @@ AirMapFlightPlanManager::submitFlightPlan()
return; return;
} }
_flightId.clear(); _flightId.clear();
emit flightIDChanged(_flightId);
_state = State::FlightSubmit; _state = State::FlightSubmit;
FlightPlans::Submit::Parameters params; FlightPlans::Submit::Parameters params;
params.authorization = _shared.loginToken().toStdString(); params.authorization = _shared.loginToken().toStdString();
@ -229,6 +235,7 @@ AirMapFlightPlanManager::submitFlightPlan()
_flightId = QString::fromStdString(_flightPlan.flight_id.get()); _flightId = QString::fromStdString(_flightPlan.flight_id.get());
_state = State::Idle; _state = State::Idle;
_pollBriefing(); _pollBriefing();
emit flightIDChanged(_flightId);
} else { } else {
QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : ""); QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
emit error("Failed to submit Flight Plan", emit error("Failed to submit Flight Plan",
@ -301,7 +308,7 @@ AirMapFlightPlanManager::_endFlight()
qCDebug(AirMapManagerLog) << "End non existing flight"; qCDebug(AirMapManagerLog) << "End non existing flight";
return; return;
} }
qCDebug(AirMapManagerLog) << "End Flight. State:" << (int)_state; qCDebug(AirMapManagerLog) << "End Flight. State:" << static_cast<int>(_state);
if(_state != State::Idle) { if(_state != State::Idle) {
QTimer::singleShot(100, this, &AirMapFlightPlanManager::_endFlight); QTimer::singleShot(100, this, &AirMapFlightPlanManager::_endFlight);
return; return;
@ -343,12 +350,12 @@ AirMapFlightPlanManager::_collectFlightDtata()
} }
//-- Get flight bounding cube and prepare (box) polygon //-- Get flight bounding cube and prepare (box) polygon
QGCGeoBoundingCube bc = *_planController->missionController()->travelBoundingCube(); QGCGeoBoundingCube bc = *_planController->missionController()->travelBoundingCube();
if(!bc.isValid() || !bc.area()) { if(!bc.isValid() || (fabs(bc.area()) < 0.0001)) {
//-- TODO: If single point, we need to set a point and a radius instead //-- TODO: If single point, we need to set a point and a radius instead
qCDebug(AirMapManagerLog) << "Not enough points for a flight plan."; qCDebug(AirMapManagerLog) << "Not enough points for a flight plan.";
return false; return false;
} }
_flight.maxAltitude = fmax(bc.pointNW.altitude(), bc.pointSE.altitude()); _flight.maxAltitude = static_cast<float>(fmax(bc.pointNW.altitude(), bc.pointSE.altitude()));
_flight.takeoffCoord = _planController->missionController()->takeoffCoordinate(); _flight.takeoffCoord = _planController->missionController()->takeoffCoordinate();
_flight.coords = bc.polygon2D(); _flight.coords = bc.polygon2D();
_flight.bc = bc; _flight.bc = bc;
@ -443,7 +450,7 @@ AirMapFlightPlanManager::_updateRulesAndFeatures(std::vector<RuleSet::Id>& rules
case AirspaceRuleFeature::Float: case AirspaceRuleFeature::Float:
//-- Sanity check for floats //-- Sanity check for floats
if(std::isfinite(feature->value().toFloat())) { if(std::isfinite(feature->value().toFloat())) {
features[feature->name().toStdString()] = RuleSet::Feature::Value(feature->value().toFloat()); features[feature->name().toStdString()] = RuleSet::Feature::Value(feature->value().toDouble());
} }
break; break;
case AirspaceRuleFeature::String: case AirspaceRuleFeature::String:
@ -467,9 +474,29 @@ AirMapFlightPlanManager::_updateRulesAndFeatures(std::vector<RuleSet::Id>& rules
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
AirMapFlightPlanManager::_updateFlightStartEndTime(DateTime& start_time, DateTime& end_time)
{
if(_flightStartTime < QDateTime::currentDateTime()) {
//-- Can't start in the past
_flightStartTime = QDateTime::currentDateTime();
emit flightStartTimeChanged();
}
quint64 startt = static_cast<quint64>(_flightStartTime.toUTC().toMSecsSinceEpoch());
start_time = airmap::from_milliseconds_since_epoch(airmap::milliseconds(static_cast<qint64>(startt)));
//-- End has to be after start
if(_flightEndTime < _flightStartTime) {
_flightEndTime = _flightStartTime.addSecs(30 * 60);
emit flightEndTimeChanged();
}
quint64 endt = static_cast<quint64>(_flightEndTime.toUTC().toMSecsSinceEpoch());
end_time = airmap::from_milliseconds_since_epoch(airmap::milliseconds(static_cast<qint64>(endt)));
}
//-----------------------------------------------------------------------------
void
AirMapFlightPlanManager::_uploadFlightPlan() AirMapFlightPlanManager::_uploadFlightPlan()
{ {
qCDebug(AirMapManagerLog) << "Uploading flight plan. State:" << (int)_state; qCDebug(AirMapManagerLog) << "Uploading flight plan. State:" << static_cast<int>(_state);
if(_state != State::Idle) { if(_state != State::Idle) {
QTimer::singleShot(100, this, &AirMapFlightPlanManager::_uploadFlightPlan); QTimer::singleShot(100, this, &AirMapFlightPlanManager::_uploadFlightPlan);
return; return;
@ -482,14 +509,12 @@ AirMapFlightPlanManager::_uploadFlightPlan()
FlightPlans::Create::Parameters params; FlightPlans::Create::Parameters params;
params.max_altitude = _flight.maxAltitude; params.max_altitude = _flight.maxAltitude;
params.min_altitude = 0.0; params.min_altitude = 0.0;
params.buffer = 2.f; params.buffer = 0.f;
params.latitude = _flight.takeoffCoord.latitude(); params.latitude = static_cast<float>(_flight.takeoffCoord.latitude());
params.longitude = _flight.takeoffCoord.longitude(); params.longitude = static_cast<float>(_flight.takeoffCoord.longitude());
params.pilot.id = _pilotID.toStdString(); params.pilot.id = _pilotID.toStdString();
quint64 start = QDateTime::currentDateTimeUtc().toMSecsSinceEpoch(); //-- Handle flight start/end
quint64 end = start + 60 * 30 * 1000; _updateFlightStartEndTime(params.start_time, params.end_time);
params.start_time = airmap::from_milliseconds_since_epoch(airmap::milliseconds((long long)start));
params.end_time = airmap::from_milliseconds_since_epoch(airmap::milliseconds((long long)end));
//-- Rules & Features //-- Rules & Features
_updateRulesAndFeatures(params.rulesets, params.features); _updateRulesAndFeatures(params.rulesets, params.features);
//-- Geometry: polygon //-- Geometry: polygon
@ -530,7 +555,7 @@ AirMapFlightPlanManager::_updateFlightPlanOnTimer()
void void
AirMapFlightPlanManager::_updateFlightPlan(bool interactive) AirMapFlightPlanManager::_updateFlightPlan(bool interactive)
{ {
qCDebug(AirMapManagerLog) << "Updating flight plan. State:" << (int)_state; qCDebug(AirMapManagerLog) << "Updating flight plan. State:" << static_cast<int>(_state);
if(_state != State::Idle) { if(_state != State::Idle) {
QTimer::singleShot(100, this, &AirMapFlightPlanManager::_updateFlightPlanOnTimer); QTimer::singleShot(100, this, &AirMapFlightPlanManager::_updateFlightPlanOnTimer);
@ -541,22 +566,19 @@ AirMapFlightPlanManager::_updateFlightPlan(bool interactive)
return; return;
} }
qCDebug(AirMapManagerLog) << "Takeoff: " << _flight.takeoffCoord;
qCDebug(AirMapManagerLog) << "Bounding box:" << _flight.bc.pointNW << _flight.bc.pointSE;
qCDebug(AirMapManagerLog) << "Flight Start:" << flightStartTime().toString();
qCDebug(AirMapManagerLog) << "Flight End: " << flightEndTime().toString();
//-- Update local instance of the flight plan //-- Update local instance of the flight plan
_flightPlan.altitude_agl.max = _flight.maxAltitude; _flightPlan.altitude_agl.max = _flight.maxAltitude;
_flightPlan.altitude_agl.min = 0.0f; _flightPlan.altitude_agl.min = 0.0f;
_flightPlan.buffer = 2.f; _flightPlan.buffer = 2.f;
_flightPlan.takeoff.latitude = _flight.takeoffCoord.latitude(); _flightPlan.takeoff.latitude = static_cast<float>(_flight.takeoffCoord.latitude());
_flightPlan.takeoff.longitude = _flight.takeoffCoord.longitude(); _flightPlan.takeoff.longitude = static_cast<float>(_flight.takeoffCoord.longitude());
//-- Rules & Features //-- Rules & Features
_flightPlan.rulesets.clear(); _flightPlan.rulesets.clear();
_flightPlan.features.clear(); _flightPlan.features.clear();
//-- If interactive, we collect features otherwise we don't //-- If interactive, we collect features otherwise we don't
_updateRulesAndFeatures(_flightPlan.rulesets, _flightPlan.features, interactive); _updateRulesAndFeatures(_flightPlan.rulesets, _flightPlan.features, interactive);
//-- Handle flight start/end
_updateFlightStartEndTime(_flightPlan.start_time, _flightPlan.end_time);
//-- Geometry: polygon //-- Geometry: polygon
Geometry::Polygon polygon; Geometry::Polygon polygon;
for (const auto& qcoord : _flight.coords) { for (const auto& qcoord : _flight.coords) {
@ -566,6 +588,12 @@ AirMapFlightPlanManager::_updateFlightPlan(bool interactive)
polygon.outer_ring.coordinates.push_back(coord); polygon.outer_ring.coordinates.push_back(coord);
} }
_flightPlan.geometry = Geometry(polygon); _flightPlan.geometry = Geometry(polygon);
qCDebug(AirMapManagerLog) << "Takeoff: " << _flight.takeoffCoord;
qCDebug(AirMapManagerLog) << "Bounding box:" << _flight.bc.pointNW << _flight.bc.pointSE;
qCDebug(AirMapManagerLog) << "Flight Start:" << flightStartTime().toString();
qCDebug(AirMapManagerLog) << "Flight End: " << flightEndTime().toString();
_state = State::FlightUpdate; _state = State::FlightUpdate;
std::weak_ptr<LifetimeChecker> isAlive(_instance); std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.doRequestWithLogin([this, isAlive](const QString& login_token) { _shared.doRequestWithLogin([this, isAlive](const QString& login_token) {
@ -647,13 +675,13 @@ AirMapFlightPlanManager::_pollBriefing()
_valid = false; _valid = false;
_advisories.clearAndDeleteContents(); _advisories.clearAndDeleteContents();
const std::vector<Status::Advisory> advisories = briefing.airspace.advisories; const std::vector<Status::Advisory> advisories = briefing.airspace.advisories;
_airspaceColor = (AirspaceAdvisoryProvider::AdvisoryColor)(int)briefing.airspace.color; _airspaceColor = static_cast<AirspaceAdvisoryProvider::AdvisoryColor>(briefing.airspace.color);
for (const auto& advisory : advisories) { for (const auto& advisory : advisories) {
AirMapAdvisory* pAdvisory = new AirMapAdvisory(this); AirMapAdvisory* pAdvisory = new AirMapAdvisory(this);
pAdvisory->_id = QString::fromStdString(advisory.airspace.id()); pAdvisory->_id = QString::fromStdString(advisory.airspace.id());
pAdvisory->_name = QString::fromStdString(advisory.airspace.name()); pAdvisory->_name = QString::fromStdString(advisory.airspace.name());
pAdvisory->_type = (AirspaceAdvisory::AdvisoryType)(int)advisory.airspace.type(); pAdvisory->_type = static_cast<AirspaceAdvisory::AdvisoryType>(advisory.airspace.type());
pAdvisory->_color = (AirspaceAdvisoryProvider::AdvisoryColor)(int)advisory.color; pAdvisory->_color = static_cast<AirspaceAdvisoryProvider::AdvisoryColor>(advisory.color);
_advisories.append(pAdvisory); _advisories.append(pAdvisory);
qCDebug(AirMapManagerLog) << "Adding briefing advisory" << pAdvisory->name(); qCDebug(AirMapManagerLog) << "Adding briefing advisory" << pAdvisory->name();
} }
@ -682,12 +710,18 @@ AirMapFlightPlanManager::_pollBriefing()
if(rule.status == RuleSet::Rule::Status::missing_info) { if(rule.status == RuleSet::Rule::Status::missing_info) {
if(!_findBriefFeature(pFeature->name())) { if(!_findBriefFeature(pFeature->name())) {
_briefFeatures.append(pFeature); _briefFeatures.append(pFeature);
_importantFeatures.append(pFeature);
qCDebug(AirMapManagerLog) << "Adding briefing feature" << pFeature->name() << pFeature->description() << pFeature->type(); qCDebug(AirMapManagerLog) << "Adding briefing feature" << pFeature->name() << pFeature->description() << pFeature->type();
} else { } else {
qCDebug(AirMapManagerLog) << "Skipping briefing feature duplicate" << pFeature->name() << pFeature->description() << pFeature->type(); qCDebug(AirMapManagerLog) << "Skipping briefing feature duplicate" << pFeature->name() << pFeature->description() << pFeature->type();
} }
} }
} }
for(const auto& feature : _importantFeatures) {
if(!_findBriefFeature(feature->name())) {
_briefFeatures.append(feature);
}
}
pRuleSet->_rules.append(pRule); pRuleSet->_rules.append(pRule);
//-- Rules separated by status for presentation //-- Rules separated by status for presentation
switch(rule.status) { switch(rule.status) {
@ -734,10 +768,6 @@ AirMapFlightPlanManager::_pollBriefing()
case Evaluation::Authorization::Status::pending: case Evaluation::Authorization::Status::pending:
pending = true; pending = true;
break; break;
//-- If we don't know, accept it
default:
accepted = true;
break;
} }
} }
if (briefing.evaluation.authorizations.size() == 0) { if (briefing.evaluation.authorizations.size() == 0) {

11
src/Airmap/AirMapFlightPlanManager.h

@ -22,6 +22,7 @@
#include "airmap/flight_plan.h" #include "airmap/flight_plan.h"
#include "airmap/ruleset.h" #include "airmap/ruleset.h"
class AirMapRuleFeature;
class PlanMasterController; class PlanMasterController;
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
@ -52,7 +53,7 @@ public:
QString startTime () override; QString startTime () override;
QString endTime () override; QString endTime () override;
QDateTime qStartTime () override; QDateTime qStartTime () override;
QGeoCoordinate takeOff () override { return QGeoCoordinate(_flight.latitude, _flight.longitude);} QGeoCoordinate takeOff () override { return QGeoCoordinate(static_cast<double>(_flight.latitude), static_cast<double>(_flight.longitude));}
QVariantList boundingBox () override { return _boundingBox; } QVariantList boundingBox () override { return _boundingBox; }
bool active () override; bool active () override;
void setEndFlight (airmap::DateTime end); void setEndFlight (airmap::DateTime end);
@ -68,7 +69,7 @@ class AirMapFlightPlanManager : public AirspaceFlightPlanProvider, public Lifeti
Q_OBJECT Q_OBJECT
public: public:
AirMapFlightPlanManager (AirMapSharedState& shared, QObject *parent = nullptr); AirMapFlightPlanManager (AirMapSharedState& shared, QObject *parent = nullptr);
~AirMapFlightPlanManager (); ~AirMapFlightPlanManager () override;
PermitStatus flightPermitStatus () const override { return _flightPermitStatus; } PermitStatus flightPermitStatus () const override { return _flightPermitStatus; }
QDateTime flightStartTime () const override; QDateTime flightStartTime () const override;
@ -102,6 +103,7 @@ public:
signals: signals:
void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails); void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
void flightIDChanged (QString flightID);
private slots: private slots:
void _pollBriefing (); void _pollBriefing ();
@ -116,6 +118,7 @@ private:
bool _collectFlightDtata (); bool _collectFlightDtata ();
void _updateFlightPlan (bool interactive = false); void _updateFlightPlan (bool interactive = false);
bool _findBriefFeature (const QString& name); bool _findBriefFeature (const QString& name);
void _updateFlightStartEndTime (airmap::DateTime& start_time, airmap::DateTime& end_time);
void _updateRulesAndFeatures (std::vector<airmap::RuleSet::Id>& rulesets, std::unordered_map<std::string, airmap::RuleSet::Feature::Value>& features, bool updateFeatures = false); void _updateRulesAndFeatures (std::vector<airmap::RuleSet::Id>& rulesets, std::unordered_map<std::string, airmap::RuleSet::Feature::Value>& features, bool updateFeatures = false);
private: private:
@ -164,6 +167,10 @@ private:
QDateTime _rangeStart; QDateTime _rangeStart;
QDateTime _rangeEnd; QDateTime _rangeEnd;
airmap::FlightPlan _flightPlan; airmap::FlightPlan _flightPlan;
QDateTime _flightStartTime;
QDateTime _flightEndTime;
QList<AirMapRuleFeature*> _importantFeatures;
AirspaceAdvisoryProvider::AdvisoryColor _airspaceColor; AirspaceAdvisoryProvider::AdvisoryColor _airspaceColor;
AirspaceFlightPlanProvider::PermitStatus _flightPermitStatus = AirspaceFlightPlanProvider::PermitNone; AirspaceFlightPlanProvider::PermitStatus _flightPermitStatus = AirspaceFlightPlanProvider::PermitNone;

6
src/Airmap/AirMapManager.cc

@ -43,9 +43,9 @@ AirMapManager::AirMapManager(QGCApplication* app, QGCToolbox* toolbox)
{ {
_logger = std::make_shared<qt::Logger>(); _logger = std::make_shared<qt::Logger>();
qt::register_types(); // TODO: still needed? qt::register_types(); // TODO: still needed?
_logger->logging_category().setEnabled(QtDebugMsg, false); _logger->logging_category().setEnabled(QtDebugMsg, true);
_logger->logging_category().setEnabled(QtInfoMsg, false); _logger->logging_category().setEnabled(QtInfoMsg, true);
_logger->logging_category().setEnabled(QtWarningMsg, false); _logger->logging_category().setEnabled(QtWarningMsg, true);
_dispatchingLogger = std::make_shared<qt::DispatchingLogger>(_logger); _dispatchingLogger = std::make_shared<qt::DispatchingLogger>(_logger);
connect(&_shared, &AirMapSharedState::error, this, &AirMapManager::_error); connect(&_shared, &AirMapSharedState::error, this, &AirMapManager::_error);
connect(&_shared, &AirMapSharedState::authStatus, this, &AirMapManager::_authStatusChanged); connect(&_shared, &AirMapSharedState::authStatus, this, &AirMapManager::_authStatusChanged);

2
src/Airmap/AirMapRulesetsManager.cc

@ -197,13 +197,11 @@ AirMapRuleSet::setSelected(bool sel)
if(_selected != sel) { if(_selected != sel) {
_selected = sel; _selected = sel;
emit selectedChanged(); emit selectedChanged();
qgcApp()->toolbox()->airspaceManager()->setUpdate();
} }
} else { } else {
if(!_selected) { if(!_selected) {
_selected = true; _selected = true;
emit selectedChanged(); emit selectedChanged();
qgcApp()->toolbox()->airspaceManager()->setUpdate();
} }
} }
} }

12
src/Airmap/AirMapTelemetry.cc

@ -77,11 +77,11 @@ AirMapTelemetry::_handleGlobalPositionInt(const mavlink_message_t& message)
mavlink_msg_global_position_int_decode(&message, &globalPosition); mavlink_msg_global_position_int_decode(&message, &globalPosition);
Telemetry::Position position{ Telemetry::Position position{
milliseconds_since_epoch(Clock::universal_time()), milliseconds_since_epoch(Clock::universal_time()),
(double) globalPosition.lat / 1e7, static_cast<double>(globalPosition.lat / 1e7),
(double) globalPosition.lon / 1e7, static_cast<double>(globalPosition.lon / 1e7),
(float) globalPosition.alt / 1000.f, static_cast<double>(globalPosition.alt) / 1000.0,
(float) globalPosition.relative_alt / 1000.f, static_cast<double>(globalPosition.relative_alt) / 1000.0,
_lastHdop static_cast<double>(_lastHdop)
}; };
Telemetry::Speed speed{ Telemetry::Speed speed{
milliseconds_since_epoch(Clock::universal_time()), milliseconds_since_epoch(Clock::universal_time()),
@ -102,7 +102,7 @@ void
AirMapTelemetry::startTelemetryStream(const QString& flightID) AirMapTelemetry::startTelemetryStream(const QString& flightID)
{ {
if (_state != State::Idle) { if (_state != State::Idle) {
qCWarning(AirMapManagerLog) << "Not starting telemetry: not in idle state:" << (int)_state; qCWarning(AirMapManagerLog) << "Not starting telemetry: not in idle state:" << static_cast<int>(_state);
return; return;
} }
if(flightID.isEmpty()) { if(flightID.isEmpty()) {

6
src/Airmap/AirMapTrafficMonitor.cc

@ -28,7 +28,11 @@ AirMapTrafficMonitor::~AirMapTrafficMonitor()
void void
AirMapTrafficMonitor::startConnection(const QString& flightID) AirMapTrafficMonitor::startConnection(const QString& flightID)
{ {
if(flightID.isEmpty() || _flightID == flightID) {
return;
}
_flightID = flightID; _flightID = flightID;
qCDebug(AirMapManagerLog) << "Traffic update started for" << flightID;
std::weak_ptr<LifetimeChecker> isAlive(_instance); std::weak_ptr<LifetimeChecker> isAlive(_instance);
auto handler = [this, isAlive](const Traffic::Monitor::Result& result) { auto handler = [this, isAlive](const Traffic::Monitor::Result& result) {
if (!isAlive.lock()) return; if (!isAlive.lock()) return;
@ -58,7 +62,7 @@ AirMapTrafficMonitor::_update(Traffic::Update::Type type, const std::vector<Traf
QString traffic_id = QString::fromStdString(traffic.id); QString traffic_id = QString::fromStdString(traffic.id);
QString vehicle_id = QString::fromStdString(traffic.aircraft_id); QString vehicle_id = QString::fromStdString(traffic.aircraft_id);
emit trafficUpdate(type == Traffic::Update::Type::alert, traffic_id, vehicle_id, emit trafficUpdate(type == Traffic::Update::Type::alert, traffic_id, vehicle_id,
QGeoCoordinate(traffic.latitude, traffic.longitude, traffic.altitude), traffic.heading); QGeoCoordinate(traffic.latitude, traffic.longitude, traffic.altitude), static_cast<float>(traffic.heading));
} }
} }

26
src/Airmap/AirMapVehicleManager.cc

@ -14,6 +14,8 @@
#include "QGCApplication.h" #include "QGCApplication.h"
#include "Vehicle.h" #include "Vehicle.h"
#include "QGCApplication.h"
#include "SettingsManager.h"
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
AirMapVehicleManager::AirMapVehicleManager(AirMapSharedState& shared, const Vehicle& vehicle) AirMapVehicleManager::AirMapVehicleManager(AirMapSharedState& shared, const Vehicle& vehicle)
@ -27,17 +29,24 @@ AirMapVehicleManager::AirMapVehicleManager(AirMapSharedState& shared, const Vehi
connect(&_telemetry, &AirMapTelemetry::error, this, &AirMapVehicleManager::error); connect(&_telemetry, &AirMapTelemetry::error, this, &AirMapVehicleManager::error);
connect(&_trafficMonitor, &AirMapTrafficMonitor::error, this, &AirMapVehicleManager::error); connect(&_trafficMonitor, &AirMapTrafficMonitor::error, this, &AirMapVehicleManager::error);
connect(&_trafficMonitor, &AirMapTrafficMonitor::trafficUpdate, this, &AirspaceVehicleManager::trafficUpdate); connect(&_trafficMonitor, &AirMapTrafficMonitor::trafficUpdate, this, &AirspaceVehicleManager::trafficUpdate);
AirMapFlightPlanManager* planMgr = qobject_cast<AirMapFlightPlanManager*>(qgcApp()->toolbox()->airspaceManager()->flightPlan());
if(planMgr) {
connect(planMgr, &AirMapFlightPlanManager::flightIDChanged, this, &AirMapVehicleManager::_flightIDChanged);
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
AirMapVehicleManager::startTelemetryStream() AirMapVehicleManager::startTelemetryStream()
{ {
AirMapFlightPlanManager* planMgr = (AirMapFlightPlanManager*)qgcApp()->toolbox()->airspaceManager()->flightPlan(); AirMapFlightPlanManager* planMgr = qobject_cast<AirMapFlightPlanManager*>(qgcApp()->toolbox()->airspaceManager()->flightPlan());
if (!planMgr->flightID().isEmpty()) { if (!planMgr->flightID().isEmpty()) {
//-- Is telemetry enabled?
if(qgcApp()->toolbox()->settingsManager()->airMapSettings()->enableTelemetry()->rawValue().toBool()) {
//-- TODO: This will start telemetry using the current flight ID in memory (current flight in AirMapFlightPlanManager) //-- TODO: This will start telemetry using the current flight ID in memory (current flight in AirMapFlightPlanManager)
qCDebug(AirMapManagerLog) << "AirMap telemetry stream enabled"; qCDebug(AirMapManagerLog) << "AirMap telemetry stream enabled";
_telemetry.startTelemetryStream(planMgr->flightID()); _telemetry.startTelemetryStream(planMgr->flightID());
}
} else { } else {
qCDebug(AirMapManagerLog) << "AirMap telemetry stream not possible (No Flight ID)"; qCDebug(AirMapManagerLog) << "AirMap telemetry stream not possible (No Flight ID)";
} }
@ -61,7 +70,7 @@ AirMapVehicleManager::isTelemetryStreaming()
void void
AirMapVehicleManager::endFlight() AirMapVehicleManager::endFlight()
{ {
AirMapFlightPlanManager* planMgr = (AirMapFlightPlanManager*)qgcApp()->toolbox()->airspaceManager()->flightPlan(); AirMapFlightPlanManager* planMgr = qobject_cast<AirMapFlightPlanManager*>(qgcApp()->toolbox()->airspaceManager()->flightPlan());
if (!planMgr->flightID().isEmpty()) { if (!planMgr->flightID().isEmpty()) {
_flightManager.endFlight(planMgr->flightID()); _flightManager.endFlight(planMgr->flightID());
} }
@ -76,3 +85,16 @@ AirMapVehicleManager::vehicleMavlinkMessageReceived(const mavlink_message_t& mes
_telemetry.vehicleMessageReceived(message); _telemetry.vehicleMessageReceived(message);
} }
} }
//-----------------------------------------------------------------------------
void
AirMapVehicleManager::_flightIDChanged(QString flightID)
{
qCDebug(AirMapManagerLog) << "Flight ID Changed:" << flightID;
//-- Handle traffic monitor
if(flightID.isEmpty()) {
_trafficMonitor.stop();
} else {
_trafficMonitor.startConnection(flightID);
}
}

7
src/Airmap/AirMapVehicleManager.h

@ -23,7 +23,7 @@ class AirMapVehicleManager : public AirspaceVehicleManager
Q_OBJECT Q_OBJECT
public: public:
AirMapVehicleManager (AirMapSharedState& shared, const Vehicle& vehicle); AirMapVehicleManager (AirMapSharedState& shared, const Vehicle& vehicle);
~AirMapVehicleManager () = default; ~AirMapVehicleManager () override = default;
void startTelemetryStream () override; void startTelemetryStream () override;
void stopTelemetryStream () override; void stopTelemetryStream () override;
@ -36,7 +36,10 @@ public slots:
void endFlight () override; void endFlight () override;
protected slots: protected slots:
virtual void vehicleMavlinkMessageReceived(const mavlink_message_t& message) override; void vehicleMavlinkMessageReceived(const mavlink_message_t& message) override;
private slots:
void _flightIDChanged (QString flightID);
private: private:
AirMapSharedState& _shared; AirMapSharedState& _shared;

1
src/Airmap/FlightBrief.qml

@ -200,6 +200,7 @@ Item {
visible: planView visible: planView
width: ScreenTools.defaultFontPixelWidth * 12 width: ScreenTools.defaultFontPixelWidth * 12
onClicked: { onClicked: {
_dirty = false
QGroundControl.airspaceManager.flightPlan.updateFlightPlan() QGroundControl.airspaceManager.flightPlan.updateFlightPlan()
} }
} }

37
src/Airmap/FlightDetails.qml

@ -2,6 +2,7 @@ import QtQuick 2.3
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4 import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2 import QtQuick.Dialogs 1.2
import QtQuick.Layouts 1.2
import QtQml 2.2 import QtQml 2.2
import QGroundControl 1.0 import QGroundControl 1.0
@ -62,23 +63,36 @@ Item {
anchors.right: parent.right anchors.right: parent.right
anchors.left: parent.left anchors.left: parent.left
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
RowLayout {
spacing: ScreenTools.defaultFontPixelWidth * 0.5
anchors.right: parent.right
anchors.left: parent.left
QGCButton {
text: qsTr("Now")
onClicked: {
_dirty = true
var today = new Date()
QGroundControl.airspaceManager.flightPlan.flightStartTime = today
timeSlider.updateTime()
}
}
QGCButton { QGCButton {
text: { text: {
var today = new Date(); var today = QGroundControl.airspaceManager.flightPlan.flightStartTime
if(datePicker.selectedDate.setHours(0,0,0,0) === today.setHours(0,0,0,0)) { if(datePicker.selectedDate.setHours(0,0,0,0) === today.setHours(0,0,0,0)) {
return qsTr("Today") return qsTr("Today")
} else { } else {
return datePicker.selectedDate.toLocaleDateString(Qt.locale()) return datePicker.selectedDate.toLocaleDateString(Qt.locale())
} }
} }
Layout.fillWidth: true
iconSource: "qrc:/airmap/expand.svg" iconSource: "qrc:/airmap/expand.svg"
anchors.right: parent.right
anchors.left: parent.left
onClicked: { onClicked: {
_dirty = true _dirty = true
datePicker.visible = true datePicker.visible = true
} }
} }
}
Item { Item {
anchors.right: parent.right anchors.right: parent.right
anchors.left: parent.left anchors.left: parent.left
@ -102,12 +116,20 @@ Item {
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
onValueChanged: { onValueChanged: {
_dirty = true _dirty = true
var today = QGroundControl.airspaceManager.flightPlan.flightStartTime
today.setHours(Math.floor(timeSlider.value * 0.25))
today.setMinutes((timeSlider.value * 15) % 60)
today.setSeconds(0)
QGroundControl.airspaceManager.flightPlan.flightStartTime = today
} }
Component.onCompleted: { Component.onCompleted: {
var today = new Date() updateTime()
}
function updateTime() {
var today = QGroundControl.airspaceManager.flightPlan.flightStartTime
var val = (((today.getHours() * 60) + today.getMinutes()) * (96/1440)) + 1 var val = (((today.getHours() * 60) + today.getMinutes()) * (96/1440)) + 1
if(val > 95) val = 95 if(val > 95) val = 95
value = Math.ceil(val) timeSlider.value = Math.ceil(val)
} }
} }
} }
@ -135,10 +157,9 @@ Item {
id: datePicker id: datePicker
anchors.centerIn: parent anchors.centerIn: parent
visible: false; visible: false;
minimumDate: { minimumDate: QGroundControl.airspaceManager.flightPlan.flightStartTime
return new Date()
}
onClicked: { onClicked: {
QGroundControl.airspaceManager.flightPlan.flightStartTime = datePicker.selectedDate
visible = false; visible = false;
} }
} }

42
src/AirspaceManagement/AirspaceManager.cc

@ -27,11 +27,11 @@ AirspaceManager::AirspaceManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox) : QGCTool(app, toolbox)
, _airspaceVisible(false) , _airspaceVisible(false)
{ {
_roiUpdateTimer.setInterval(2000); _ruleUpdateTimer.setInterval(2000);
_roiUpdateTimer.setSingleShot(true); _ruleUpdateTimer.setSingleShot(true);
_updateTimer.setInterval(1000); _updateTimer.setInterval(1000);
_updateTimer.setSingleShot(true); _updateTimer.setSingleShot(true);
connect(&_roiUpdateTimer, &QTimer::timeout, this, &AirspaceManager::_updateToROITimeout); connect(&_ruleUpdateTimer, &QTimer::timeout, this, &AirspaceManager::_updateRulesTimeout);
connect(&_updateTimer, &QTimer::timeout, this, &AirspaceManager::_updateTimeout); connect(&_updateTimer, &QTimer::timeout, this, &AirspaceManager::_updateTimeout);
qmlRegisterUncreatableType<AirspaceAdvisoryProvider> ("QGroundControl.Airspace", 1, 0, "AirspaceAdvisoryProvider", "Reference only"); qmlRegisterUncreatableType<AirspaceAdvisoryProvider> ("QGroundControl.Airspace", 1, 0, "AirspaceAdvisoryProvider", "Reference only");
qmlRegisterUncreatableType<AirspaceFlightPlanProvider> ("QGroundControl.Airspace", 1, 0, "AirspaceFlightPlanProvider", "Reference only"); qmlRegisterUncreatableType<AirspaceFlightPlanProvider> ("QGroundControl.Airspace", 1, 0, "AirspaceFlightPlanProvider", "Reference only");
@ -77,6 +77,10 @@ AirspaceManager::setToolbox(QGCToolbox* toolbox)
_advisories = _instatiateAirspaceAdvisoryProvider(); _advisories = _instatiateAirspaceAdvisoryProvider();
_airspaces = _instantiateAirspaceRestrictionProvider(); _airspaces = _instantiateAirspaceRestrictionProvider();
_flightPlan = _instantiateAirspaceFlightPlanProvider(); _flightPlan = _instantiateAirspaceFlightPlanProvider();
//-- Keep track of rule changes
if(_ruleSetsProvider) {
connect(_ruleSetsProvider, &AirspaceRulesetsProvider::selectedRuleSetsChanged, this, &AirspaceManager::_rulesChanged);
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
@ -107,21 +111,13 @@ AirspaceManager::setROI(const QGeoCoordinate& pointNW, const QGeoCoordinate& poi
} }
} }
//-----------------------------------------------------------------------------
void
AirspaceManager::setUpdate()
{
_updateTimer.start();
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
AirspaceManager::_setROI(const QGCGeoBoundingCube& roi) AirspaceManager::_setROI(const QGCGeoBoundingCube& roi)
{ {
if(_roi != roi) { if(_roi != roi) {
_roi = roi; _roi = roi;
_roiUpdateTimer.start(); _ruleUpdateTimer.start();
} }
} }
@ -129,9 +125,6 @@ AirspaceManager::_setROI(const QGCGeoBoundingCube& roi)
void void
AirspaceManager::_updateToROI(bool reset) AirspaceManager::_updateToROI(bool reset)
{ {
if(reset) {
_updateTimer.stop();
}
if(_airspaces) { if(_airspaces) {
_airspaces->setROI(_roi, reset); _airspaces->setROI(_roi, reset);
} }
@ -141,21 +134,28 @@ AirspaceManager::_updateToROI(bool reset)
if(_weatherProvider) { if(_weatherProvider) {
_weatherProvider->setROI(_roi, reset); _weatherProvider->setROI(_roi, reset);
} }
if (_advisories) {
_advisories->setROI(_roi, reset);
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
AirspaceManager::_updateToROITimeout() AirspaceManager::_updateTimeout()
{ {
_updateToROI(false); _updateToROI(false);
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
AirspaceManager::_updateTimeout() AirspaceManager::_rulesChanged()
{ {
emit update(); _ruleUpdateTimer.start();
}
//-----------------------------------------------------------------------------
void
AirspaceManager::_updateRulesTimeout()
{
if (_advisories) {
_advisories->setROI(_roi, true);
}
} }

7
src/AirspaceManagement/AirspaceManager.h

@ -93,7 +93,6 @@ public:
virtual void setAirspaceVisible (bool set) { _airspaceVisible = set; emit airspaceVisibleChanged(); } virtual void setAirspaceVisible (bool set) { _airspaceVisible = set; emit airspaceVisibleChanged(); }
virtual bool connected () const = 0; virtual bool connected () const = 0;
virtual QString connectStatus () const { return QString(); } virtual QString connectStatus () const { return QString(); }
virtual void setUpdate ();
virtual AirspaceManager::AuthStatus authStatus () const { return Anonymous; } virtual AirspaceManager::AuthStatus authStatus () const { return Anonymous; }
@ -107,7 +106,6 @@ signals:
void connectedChanged (); void connectedChanged ();
void connectStatusChanged (); void connectStatusChanged ();
void authStatusChanged (); void authStatusChanged ();
void update ();
protected: protected:
/** /**
@ -133,13 +131,14 @@ protected:
AirspaceAdvisoryProvider* _advisories = nullptr; ///< Advisory info AirspaceAdvisoryProvider* _advisories = nullptr; ///< Advisory info
AirspaceRestrictionProvider* _airspaces = nullptr; ///< Airspace info AirspaceRestrictionProvider* _airspaces = nullptr; ///< Airspace info
AirspaceFlightPlanProvider* _flightPlan = nullptr; ///< Flight plan management AirspaceFlightPlanProvider* _flightPlan = nullptr; ///< Flight plan management
QTimer _roiUpdateTimer; QTimer _ruleUpdateTimer;
QTimer _updateTimer; QTimer _updateTimer;
QGCGeoBoundingCube _roi; QGCGeoBoundingCube _roi;
private slots: private slots:
void _updateToROITimeout (); void _updateRulesTimeout ();
void _updateTimeout (); void _updateTimeout ();
void _rulesChanged ();
private: private:
void _updateToROI (bool reset = false); void _updateToROI (bool reset = false);

7
src/FlightDisplay/FlightDisplayViewMap.qml

@ -167,13 +167,6 @@ FlightMap {
QGCMapPalette { id: mapPal; lightColors: isSatelliteMap } QGCMapPalette { id: mapPal; lightColors: isSatelliteMap }
Connections { Connections {
target: QGroundControl.airspaceManager
onUpdate: {
updateAirspace(true)
}
}
Connections {
target: _missionController target: _missionController
onNewItemsFromVehicle: { onNewItemsFromVehicle: {

3
src/PlanView/PlanView.qml

@ -185,9 +185,6 @@ QGCView {
onAirspaceVisibleChanged: { onAirspaceVisibleChanged: {
planControlColapsed = QGroundControl.airspaceManager.airspaceVisible planControlColapsed = QGroundControl.airspaceManager.airspaceVisible
} }
onUpdate: {
updateAirspace(true)
}
} }
Component { Component {

Loading…
Cancel
Save