Commit 4faf39fd authored by DonLakeFlyer's avatar DonLakeFlyer

Don't query terrain from Fly View

parent 535ff2ab
...@@ -109,7 +109,7 @@ QGCView { ...@@ -109,7 +109,7 @@ QGCView {
PlanMasterController { PlanMasterController {
id: masterController id: masterController
Component.onCompleted: start(false /* editMode */) Component.onCompleted: start(true /* flyView */)
} }
Connections { Connections {
......
This diff is collapsed.
...@@ -11,8 +11,8 @@ ...@@ -11,8 +11,8 @@
const char* ComplexMissionItem::jsonComplexItemTypeKey = "complexItemType"; const char* ComplexMissionItem::jsonComplexItemTypeKey = "complexItemType";
ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, QObject* parent) ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
: VisualMissionItem(vehicle, parent) : VisualMissionItem(vehicle, flyView, parent)
{ {
} }
......
...@@ -17,7 +17,7 @@ class ComplexMissionItem : public VisualMissionItem ...@@ -17,7 +17,7 @@ class ComplexMissionItem : public VisualMissionItem
Q_OBJECT Q_OBJECT
public: public:
ComplexMissionItem(Vehicle* vehicle, QObject* parent = NULL); ComplexMissionItem(Vehicle* vehicle, bool flyView, QObject* parent);
const ComplexMissionItem& operator=(const ComplexMissionItem& other); const ComplexMissionItem& operator=(const ComplexMissionItem& other);
......
...@@ -27,8 +27,8 @@ const char* CorridorScanComplexItem::_jsonEntryPointKey = "EntryPoint"; ...@@ -27,8 +27,8 @@ const char* CorridorScanComplexItem::_jsonEntryPointKey = "EntryPoint";
const char* CorridorScanComplexItem::jsonComplexItemTypeValue = "CorridorScan"; const char* CorridorScanComplexItem::jsonComplexItemTypeValue = "CorridorScan";
CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, QObject* parent) CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, bool flyView, QObject* parent)
: TransectStyleComplexItem (vehicle, settingsGroup, parent) : TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent)
, _entryPoint (0) , _entryPoint (0)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CorridorScan.SettingsGroup.json"), this)) , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CorridorScan.SettingsGroup.json"), this))
, _corridorWidthFact (settingsGroup, _metaDataMap[corridorWidthName]) , _corridorWidthFact (settingsGroup, _metaDataMap[corridorWidthName])
......
...@@ -23,7 +23,7 @@ class CorridorScanComplexItem : public TransectStyleComplexItem ...@@ -23,7 +23,7 @@ class CorridorScanComplexItem : public TransectStyleComplexItem
Q_OBJECT Q_OBJECT
public: public:
CorridorScanComplexItem(Vehicle* vehicle, QObject* parent = NULL); CorridorScanComplexItem(Vehicle* vehicle, bool flyView, QObject* parent);
Q_PROPERTY(QGCMapPolyline* corridorPolyline READ corridorPolyline CONSTANT) Q_PROPERTY(QGCMapPolyline* corridorPolyline READ corridorPolyline CONSTANT)
Q_PROPERTY(Fact* corridorWidth READ corridorWidth CONSTANT) Q_PROPERTY(Fact* corridorWidth READ corridorWidth CONSTANT)
......
...@@ -23,7 +23,7 @@ void CorridorScanComplexItemTest::init(void) ...@@ -23,7 +23,7 @@ void CorridorScanComplexItemTest::init(void)
UnitTest::init(); UnitTest::init();
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this); _offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_corridorItem = new CorridorScanComplexItem(_offlineVehicle, this); _corridorItem = new CorridorScanComplexItem(_offlineVehicle, false /* flyView */, this);
// vehicleSpeed need for terrain calcs // vehicleSpeed need for terrain calcs
MissionController::MissionFlightStatus_t missionFlightStatus; MissionController::MissionFlightStatus_t missionFlightStatus;
......
...@@ -39,8 +39,8 @@ const char* FixedWingLandingComplexItem::_jsonFallRateKey = "fal ...@@ -39,8 +39,8 @@ const char* FixedWingLandingComplexItem::_jsonFallRateKey = "fal
const char* FixedWingLandingComplexItem::_jsonLandingAltitudeRelativeKey = "landAltitudeRelative"; const char* FixedWingLandingComplexItem::_jsonLandingAltitudeRelativeKey = "landAltitudeRelative";
const char* FixedWingLandingComplexItem::_jsonLoiterAltitudeRelativeKey = "loiterAltitudeRelative"; const char* FixedWingLandingComplexItem::_jsonLoiterAltitudeRelativeKey = "loiterAltitudeRelative";
FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObject* parent) FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool flyView, QObject* parent)
: ComplexMissionItem (vehicle, parent) : ComplexMissionItem (vehicle, flyView, parent)
, _sequenceNumber (0) , _sequenceNumber (0)
, _dirty (false) , _dirty (false)
, _landingCoordSet (false) , _landingCoordSet (false)
...@@ -283,7 +283,7 @@ void FixedWingLandingComplexItem::appendMissionItems(QList<MissionItem*>& items, ...@@ -283,7 +283,7 @@ void FixedWingLandingComplexItem::appendMissionItems(QList<MissionItem*>& items,
items.append(item); items.append(item);
} }
bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, Vehicle* vehicle) bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, bool flyView, Vehicle* vehicle)
{ {
qCDebug(FixedWingLandingComplexItemLog) << "FixedWingLandingComplexItem::scanForItem count" << visualItems->count(); qCDebug(FixedWingLandingComplexItemLog) << "FixedWingLandingComplexItem::scanForItem count" << visualItems->count();
...@@ -328,7 +328,7 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, V ...@@ -328,7 +328,7 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, V
// We made it this far so we do have a Fixed Wing Landing Pattern item at the end of the mission // We made it this far so we do have a Fixed Wing Landing Pattern item at the end of the mission
FixedWingLandingComplexItem* complexItem = new FixedWingLandingComplexItem(vehicle, visualItems); FixedWingLandingComplexItem* complexItem = new FixedWingLandingComplexItem(vehicle, flyView, visualItems);
complexItem->_ignoreRecalcSignals = true; complexItem->_ignoreRecalcSignals = true;
......
...@@ -22,7 +22,7 @@ class FixedWingLandingComplexItem : public ComplexMissionItem ...@@ -22,7 +22,7 @@ class FixedWingLandingComplexItem : public ComplexMissionItem
Q_OBJECT Q_OBJECT
public: public:
FixedWingLandingComplexItem(Vehicle* vehicle, QObject* parent = NULL); FixedWingLandingComplexItem(Vehicle* vehicle, bool flyView, QObject* parent);
Q_PROPERTY(Fact* loiterAltitude READ loiterAltitude CONSTANT) Q_PROPERTY(Fact* loiterAltitude READ loiterAltitude CONSTANT)
Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT) Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT)
...@@ -52,7 +52,7 @@ public: ...@@ -52,7 +52,7 @@ public:
void setLoiterCoordinate (const QGeoCoordinate& coordinate); void setLoiterCoordinate (const QGeoCoordinate& coordinate);
/// Scans the loaded items for a landing pattern complex item /// Scans the loaded items for a landing pattern complex item
static bool scanForItem(QmlObjectListModel* visualItems, Vehicle* vehicle); static bool scanForItem(QmlObjectListModel* visualItems, bool flyView, Vehicle* vehicle);
// Overrides from ComplexMissionItem // Overrides from ComplexMissionItem
......
...@@ -54,11 +54,11 @@ GeoFenceController::~GeoFenceController() ...@@ -54,11 +54,11 @@ GeoFenceController::~GeoFenceController()
} }
void GeoFenceController::start(bool editMode) void GeoFenceController::start(bool flyView)
{ {
qCDebug(GeoFenceControllerLog) << "start editMode" << editMode; qCDebug(GeoFenceControllerLog) << "start flyView" << flyView;
PlanElementController::start(editMode); PlanElementController::start(flyView);
_init(); _init();
} }
...@@ -269,7 +269,7 @@ void GeoFenceController::_managerLoadComplete(void) ...@@ -269,7 +269,7 @@ void GeoFenceController::_managerLoadComplete(void)
{ {
// Fly view always reloads on _loadComplete // Fly view always reloads on _loadComplete
// Plan view only reloads on _loadComplete if specifically requested // Plan view only reloads on _loadComplete if specifically requested
if (!_editMode || _itemsRequested) { if (_flyView || _itemsRequested) {
_setReturnPointFromManager(_geoFenceManager->breachReturnPoint()); _setReturnPointFromManager(_geoFenceManager->breachReturnPoint());
_setFenceFromManager(_geoFenceManager->polygons(), _geoFenceManager->circles()); _setFenceFromManager(_geoFenceManager->polygons(), _geoFenceManager->circles());
setDirty(false); setDirty(false);
...@@ -282,7 +282,7 @@ void GeoFenceController::_managerLoadComplete(void) ...@@ -282,7 +282,7 @@ void GeoFenceController::_managerLoadComplete(void)
void GeoFenceController::_managerSendComplete(bool error) void GeoFenceController::_managerSendComplete(bool error)
{ {
// Fly view always reloads on manager sendComplete // Fly view always reloads on manager sendComplete
if (!error && !_editMode) { if (!error && _flyView) {
showPlanFromManagerVehicle(); showPlanFromManagerVehicle();
} }
} }
...@@ -307,7 +307,7 @@ void GeoFenceController::_updateContainsItems(void) ...@@ -307,7 +307,7 @@ void GeoFenceController::_updateContainsItems(void)
bool GeoFenceController::showPlanFromManagerVehicle(void) bool GeoFenceController::showPlanFromManagerVehicle(void)
{ {
qCDebug(GeoFenceControllerLog) << "showPlanFromManagerVehicle" << _editMode; qCDebug(GeoFenceControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
if (_masterController->offline()) { if (_masterController->offline()) {
qCWarning(GeoFenceControllerLog) << "GeoFenceController::showPlanFromManagerVehicle called while offline"; qCWarning(GeoFenceControllerLog) << "GeoFenceController::showPlanFromManagerVehicle called while offline";
return true; // stops further propagation of showPlanFromManagerVehicle due to error return true; // stops further propagation of showPlanFromManagerVehicle due to error
......
...@@ -62,7 +62,7 @@ public: ...@@ -62,7 +62,7 @@ public:
// Overrides from PlanElementController // Overrides from PlanElementController
bool supported (void) const final; bool supported (void) const final;
void start (bool editMode) final; void start (bool flyView) final;
void save (QJsonObject& json) final; void save (QJsonObject& json) final;
bool load (const QJsonObject& json, QString& errorString) final; bool load (const QJsonObject& json, QString& errorString) final;
void loadFromVehicle (void) final; void loadFromVehicle (void) final;
......
This diff is collapsed.
...@@ -129,7 +129,7 @@ public: ...@@ -129,7 +129,7 @@ public:
// Overrides from PlanElementController // Overrides from PlanElementController
bool supported (void) const final { return true; } bool supported (void) const final { return true; }
void start (bool editMode) final; void start (bool flyView) final;
void save (QJsonObject& json) final; void save (QJsonObject& json) final;
bool load (const QJsonObject& json, QString& errorString) final; bool load (const QJsonObject& json, QString& errorString) final;
void loadFromVehicle (void) final; void loadFromVehicle (void) final;
......
...@@ -59,7 +59,7 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType) ...@@ -59,7 +59,7 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
Q_CHECK_PTR(_multiSpyMissionController); Q_CHECK_PTR(_multiSpyMissionController);
QCOMPARE(_multiSpyMissionController->init(_missionController, _rgMissionControllerSignals, _cMissionControllerSignals), true); QCOMPARE(_multiSpyMissionController->init(_missionController, _rgMissionControllerSignals, _cMissionControllerSignals), true);
_masterController->start(true /* editMode */); _masterController->start(false /* flyView */);
// All signals should some through on start // All signals should some through on start
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(visualItemsChangedSignalMask | waypointLinesChangedSignalMask), true); QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(visualItemsChangedSignalMask | waypointLinesChangedSignalMask), true);
...@@ -166,7 +166,7 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp ...@@ -166,7 +166,7 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp
// Start offline and add item // Start offline and add item
_missionController = new MissionController(); _missionController = new MissionController();
Q_CHECK_PTR(_missionController); Q_CHECK_PTR(_missionController);
_missionController->start(true /* editMode */); _missionController->start(false /* flyView */);
_missionController->insertSimpleMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->visualItems()->count()); _missionController->insertSimpleMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->visualItems()->count());
// Go online to empty vehicle // Go online to empty vehicle
......
...@@ -282,7 +282,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void) ...@@ -282,7 +282,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void)
{ {
// We specifically test SimpleMissionItem loading as well since it has additional // We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values. // signalling which can affect values.
SimpleMissionItem simpleMissionItem(_offlineVehicle); SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, NULL);
QString testString("10\t0\t3\t80\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n"); QString testString("10\t0\t3\t80\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n");
QTextStream testStream(&testString, QIODevice::ReadOnly); QTextStream testStream(&testString, QIODevice::ReadOnly);
...@@ -452,7 +452,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void) ...@@ -452,7 +452,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void)
// We specifically test SimpleMissionItem loading as well since it has additional // We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values. // signalling which can affect values.
SimpleMissionItem simpleMissionItem(_offlineVehicle); SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, NULL);
QString errorString; QString errorString;
QJsonArray coordinateArray; QJsonArray coordinateArray;
QJsonObject jsonObject; QJsonObject jsonObject;
......
...@@ -27,9 +27,8 @@ const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHome ...@@ -27,9 +27,8 @@ const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHome
QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap; QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap;
MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool planView, QObject* parent) MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject* parent)
: ComplexMissionItem (vehicle, parent) : ComplexMissionItem (vehicle, flyView, parent)
, _planView (planView)
, _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble) , _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble)
, _plannedHomePositionFromVehicle (false) , _plannedHomePositionFromVehicle (false)
, _missionEndRTL (false) , _missionEndRTL (false)
...@@ -303,5 +302,5 @@ void MissionSettingsItem::_setHomeAltFromTerrain(double terrainAltitude) ...@@ -303,5 +302,5 @@ void MissionSettingsItem::_setHomeAltFromTerrain(double terrainAltitude)
QString MissionSettingsItem::abbreviation(void) const QString MissionSettingsItem::abbreviation(void) const
{ {
return _planView ? tr("Planned Home") : tr("H"); return _flyView ? tr("H") : tr("Planned Home");
} }
...@@ -24,7 +24,7 @@ class MissionSettingsItem : public ComplexMissionItem ...@@ -24,7 +24,7 @@ class MissionSettingsItem : public ComplexMissionItem
Q_OBJECT Q_OBJECT
public: public:
MissionSettingsItem(Vehicle* vehicle, bool planView, QObject* parent = NULL); MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject* parent);
Q_PROPERTY(Fact* plannedHomePositionAltitude READ plannedHomePositionAltitude CONSTANT) Q_PROPERTY(Fact* plannedHomePositionAltitude READ plannedHomePositionAltitude CONSTANT)
Q_PROPERTY(bool missionEndRTL READ missionEndRTL WRITE setMissionEndRTL NOTIFY missionEndRTLChanged) Q_PROPERTY(bool missionEndRTL READ missionEndRTL WRITE setMissionEndRTL NOTIFY missionEndRTLChanged)
...@@ -101,7 +101,6 @@ private slots: ...@@ -101,7 +101,6 @@ private slots:
void _setHomeAltFromTerrain (double terrainAltitude); void _setHomeAltFromTerrain (double terrainAltitude);
private: private:
bool _planView;
QGeoCoordinate _plannedHomePositionCoordinate; // Does not include altitude QGeoCoordinate _plannedHomePositionCoordinate; // Does not include altitude
Fact _plannedHomePositionAltitudeFact; Fact _plannedHomePositionAltitudeFact;
bool _plannedHomePositionFromVehicle; bool _plannedHomePositionFromVehicle;
......
...@@ -22,7 +22,7 @@ void MissionSettingsTest::init(void) ...@@ -22,7 +22,7 @@ void MissionSettingsTest::init(void)
{ {
VisualMissionItemTest::init(); VisualMissionItemTest::init();
_settingsItem = new MissionSettingsItem(_offlineVehicle, true /* planView */, this); _settingsItem = new MissionSettingsItem(_offlineVehicle, false /* flyView */, this);
} }
void MissionSettingsTest::cleanup(void) void MissionSettingsTest::cleanup(void)
......
...@@ -15,11 +15,11 @@ ...@@ -15,11 +15,11 @@
#include "AppSettings.h" #include "AppSettings.h"
PlanElementController::PlanElementController(PlanMasterController* masterController, QObject* parent) PlanElementController::PlanElementController(PlanMasterController* masterController, QObject* parent)
: QObject(parent) : QObject (parent)
, _masterController(masterController) , _masterController (masterController)
, _controllerVehicle(masterController->controllerVehicle()) , _controllerVehicle(masterController->controllerVehicle())
, _managerVehicle(masterController->managerVehicle()) , _managerVehicle (masterController->managerVehicle())
, _editMode(false) , _flyView (false)
{ {
} }
...@@ -29,9 +29,9 @@ PlanElementController::~PlanElementController() ...@@ -29,9 +29,9 @@ PlanElementController::~PlanElementController()
} }
void PlanElementController::start(bool editMode) void PlanElementController::start(bool flyView)
{ {
_editMode = editMode; _flyView = flyView;
} }
void PlanElementController::managerVehicleChanged(Vehicle* managerVehicle) void PlanElementController::managerVehicleChanged(Vehicle* managerVehicle)
......
...@@ -33,8 +33,7 @@ public: ...@@ -33,8 +33,7 @@ public:
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< true: unsaved/sent changes are present, false: no changes since last save/send Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< true: unsaved/sent changes are present, false: no changes since last save/send
/// Should be called immediately upon Component.onCompleted. /// Should be called immediately upon Component.onCompleted.
/// @param editMode true: controller being used in Plan view, false: controller being used in Fly view virtual void start(bool flyView);
virtual void start(bool editMode);
virtual void save (QJsonObject& json) = 0; virtual void save (QJsonObject& json) = 0;
virtual bool load (const QJsonObject& json, QString& errorString) = 0; virtual bool load (const QJsonObject& json, QString& errorString) = 0;
...@@ -72,7 +71,7 @@ protected: ...@@ -72,7 +71,7 @@ protected:
PlanMasterController* _masterController; PlanMasterController* _masterController;
Vehicle* _controllerVehicle; ///< Offline controller vehicle Vehicle* _controllerVehicle; ///< Offline controller vehicle
Vehicle* _managerVehicle; ///< Either active vehicle or _controllerVehicle if none Vehicle* _managerVehicle; ///< Either active vehicle or _controllerVehicle if none
bool _editMode; bool _flyView;
}; };
#endif #endif
...@@ -29,20 +29,20 @@ const char* PlanMasterController::_jsonGeoFenceObjectKey = "geoFence"; ...@@ -29,20 +29,20 @@ const char* PlanMasterController::_jsonGeoFenceObjectKey = "geoFence";
const char* PlanMasterController::_jsonRallyPointsObjectKey = "rallyPoints"; const char* PlanMasterController::_jsonRallyPointsObjectKey = "rallyPoints";
PlanMasterController::PlanMasterController(QObject* parent) PlanMasterController::PlanMasterController(QObject* parent)
: QObject(parent) : QObject (parent)
, _multiVehicleMgr(qgcApp()->toolbox()->multiVehicleManager()) , _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager())
, _controllerVehicle(new Vehicle((MAV_AUTOPILOT)qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->rawValue().toInt(), (MAV_TYPE)qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingVehicleType()->rawValue().toInt(), qgcApp()->toolbox()->firmwarePluginManager())) , _controllerVehicle (new Vehicle((MAV_AUTOPILOT)qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->rawValue().toInt(), (MAV_TYPE)qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingVehicleType()->rawValue().toInt(), qgcApp()->toolbox()->firmwarePluginManager()))
, _managerVehicle(_controllerVehicle) , _managerVehicle (_controllerVehicle)
, _editMode(false) , _flyView (true)
, _offline(true) , _offline (true)
, _missionController(this) , _missionController (this)
, _geoFenceController(this) , _geoFenceController (this)
, _rallyPointController(this) , _rallyPointController (this)
, _loadGeoFence(false) , _loadGeoFence (false)
, _loadRallyPoints(false) , _loadRallyPoints (false)
, _sendGeoFence(false) , _sendGeoFence (false)
, _sendRallyPoints(false) , _sendRallyPoints (false)
, _syncInProgress(false) , _syncInProgress (false)
{ {
connect(&_missionController, &MissionController::dirtyChanged, this, &PlanMasterController::dirtyChanged); connect(&_missionController, &MissionController::dirtyChanged, this, &PlanMasterController::dirtyChanged);
connect(&_geoFenceController, &GeoFenceController::dirtyChanged, this, &PlanMasterController::dirtyChanged); connect(&_geoFenceController, &GeoFenceController::dirtyChanged, this, &PlanMasterController::dirtyChanged);
...@@ -62,12 +62,12 @@ PlanMasterController::~PlanMasterController() ...@@ -62,12 +62,12 @@ PlanMasterController::~PlanMasterController()
} }
void PlanMasterController::start(bool editMode) void PlanMasterController::start(bool flyView)
{ {
_editMode = editMode; _flyView = flyView;
_missionController.start(editMode); _missionController.start(_flyView);
_geoFenceController.start(editMode); _geoFenceController.start(_flyView);
_rallyPointController.start(editMode); _rallyPointController.start(_flyView);
connect(_multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &PlanMasterController::_activeVehicleChanged); connect(_multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &PlanMasterController::_activeVehicleChanged);
_activeVehicleChanged(_multiVehicleMgr->activeVehicle()); _activeVehicleChanged(_multiVehicleMgr->activeVehicle());
...@@ -75,10 +75,10 @@ void PlanMasterController::start(bool editMode) ...@@ -75,10 +75,10 @@ void PlanMasterController::start(bool editMode)
void PlanMasterController::startStaticActiveVehicle(Vehicle* vehicle) void PlanMasterController::startStaticActiveVehicle(Vehicle* vehicle)
{ {
_editMode = false; _flyView = true;
_missionController.start(false); _missionController.start(_flyView);
_geoFenceController.start(false); _geoFenceController.start(_flyView);
_rallyPointController.start(false); _rallyPointController.start(_flyView);
_activeVehicleChanged(vehicle); _activeVehicleChanged(vehicle);
} }
...@@ -132,7 +132,7 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) ...@@ -132,7 +132,7 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
_geoFenceController.managerVehicleChanged(_managerVehicle); _geoFenceController.managerVehicleChanged(_managerVehicle);
_rallyPointController.managerVehicleChanged(_managerVehicle); _rallyPointController.managerVehicleChanged(_managerVehicle);
if (_editMode) { if (!_flyView) {
if (!offline()) { if (!offline()) {
// We are in Plan view and we have a newly connected vehicle: // We are in Plan view and we have a newly connected vehicle:
// - If there is no plan available in Plan view show the one from the vehicle // - If there is no plan available in Plan view show the one from the vehicle
...@@ -164,7 +164,7 @@ void PlanMasterController::loadFromVehicle(void) ...@@ -164,7 +164,7 @@ void PlanMasterController::loadFromVehicle(void)
if (offline()) { if (offline()) {
qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called while offline"; qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called while offline";
} else if (!_editMode) { } else if (_flyView) {
qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called from Fly view"; qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called from Fly view";
} else if (syncInProgress()) { } else if (syncInProgress()) {
qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called while syncInProgress"; qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called while syncInProgress";
...@@ -181,7 +181,7 @@ void PlanMasterController::loadFromVehicle(void) ...@@ -181,7 +181,7 @@ void PlanMasterController::loadFromVehicle(void)
void PlanMasterController::_loadMissionComplete(void) void PlanMasterController::_loadMissionComplete(void)
{ {
if (_editMode && _loadGeoFence) { if (!_flyView && _loadGeoFence) {
_loadGeoFence = false; _loadGeoFence = false;
_loadRallyPoints = true; _loadRallyPoints = true;
if (_geoFenceController.supported()) { if (_geoFenceController.supported()) {
...@@ -198,7 +198,7 @@ void PlanMasterController::_loadMissionComplete(void) ...@@ -198,7 +198,7 @@ void PlanMasterController::_loadMissionComplete(void)
void PlanMasterController::_loadGeoFenceComplete(void) void PlanMasterController::_loadGeoFenceComplete(void)
{ {
if (_editMode && _loadRallyPoints) { if (!_flyView && _loadRallyPoints) {
_loadRallyPoints = false; _loadRallyPoints = false;
if (_rallyPointController.supported()) { if (_rallyPointController.supported()) {
qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadGeoFenceComplete _rallyPointController.loadFromVehicle"; qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadGeoFenceComplete _rallyPointController.loadFromVehicle";
...@@ -214,7 +214,7 @@ void PlanMasterController::_loadGeoFenceComplete(void) ...@@ -214,7 +214,7 @@ void PlanMasterController::_loadGeoFenceComplete(void)
void PlanMasterController::_loadRallyPointsComplete(void) void PlanMasterController::_loadRallyPointsComplete(void)
{ {
if (_editMode) { if (!_flyView) {
_syncInProgress = false; _syncInProgress = false;
emit syncInProgressChanged(false); emit syncInProgressChanged(false);
} }
......
...@@ -46,8 +46,7 @@ public: ...@@ -46,8 +46,7 @@ public:
Q_PROPERTY(QStringList saveKmlFilters READ saveKmlFilters CONSTANT) ///< File filter list saving KML files Q_PROPERTY(QStringList saveKmlFilters READ saveKmlFilters CONSTANT) ///< File filter list saving KML files
/// Should be called immediately upon Component.onCompleted. /// Should be called immediately upon Component.onCompleted.
/// @param editMode true: controller being used in Plan view, false: controller being used in Fly view Q_INVOKABLE void start(bool flyView);
Q_INVOKABLE void start(bool editMode);
/// Starts the controller using a single static active vehicle. Will not track global active vehicle changes. /// Starts the controller using a single static active vehicle. Will not track global active vehicle changes.
Q_INVOKABLE void startStaticActiveVehicle(Vehicle* vehicle); Q_INVOKABLE void startStaticActiveVehicle(Vehicle* vehicle);
...@@ -111,7 +110,7 @@ private: ...@@ -111,7 +110,7 @@ private:
MultiVehicleManager* _multiVehicleMgr; MultiVehicleManager* _multiVehicleMgr;
Vehicle* _controllerVehicle; ///< Offline controller vehicle Vehicle* _controllerVehicle; ///< Offline controller vehicle
Vehicle* _managerVehicle; ///< Either active vehicle or _controllerVehicle if none Vehicle* _managerVehicle; ///< Either active vehicle or _controllerVehicle if none
bool _editMode; bool _flyView;
bool _offline; bool _offline;
MissionController _missionController; MissionController _missionController;
GeoFenceController _geoFenceController; GeoFenceController _geoFenceController;
......
...@@ -27,7 +27,7 @@ void PlanMasterControllerTest::init(void) ...@@ -27,7 +27,7 @@ void PlanMasterControllerTest::init(void)
UnitTest::init(); UnitTest::init();
_masterController = new PlanMasterController(this); _masterController = new PlanMasterController(this);
_masterController->start(true /* editMode */); _masterController->start(false /* flyView */);
} }
void PlanMasterControllerTest::cleanup(void) void PlanMasterControllerTest::cleanup(void)
......
...@@ -192,7 +192,7 @@ void RallyPointController::_managerLoadComplete(const QList<QGeoCoordinate> rgPo ...@@ -192,7 +192,7 @@ void RallyPointController::_managerLoadComplete(const QList<QGeoCoordinate> rgPo
{ {
// Fly view always reloads on _loadComplete // Fly view always reloads on _loadComplete
// Plan view only reloads on _loadComplete if specifically requested // Plan view only reloads on _loadComplete if specifically requested
if (!_editMode || _itemsRequested) { if (_flyView || _itemsRequested) {
_points.clearAndDeleteContents(); _points.clearAndDeleteContents();
QObjectList pointList; QObjectList pointList;
for (int i=0; i<rgPoints.count(); i++) { for (int i=0; i<rgPoints.count(); i++) {
...@@ -209,7 +209,7 @@ void RallyPointController::_managerLoadComplete(const QList<QGeoCoordinate> rgPo ...@@ -209,7 +209,7 @@ void RallyPointController::_managerLoadComplete(const QList<QGeoCoordinate> rgPo
void RallyPointController::_managerSendComplete(bool error) void RallyPointController::_managerSendComplete(bool error)
{ {
// Fly view always reloads after send // Fly view always reloads after send
if (!error && _editMode) { if (!error && !_flyView) {
showPlanFromManagerVehicle(); showPlanFromManagerVehicle();
} }
} }
...@@ -286,7 +286,7 @@ void RallyPointController::_updateContainsItems(void) ...@@ -286,7 +286,7 @@ void RallyPointController::_updateContainsItems(void)
bool RallyPointController::showPlanFromManagerVehicle (void) bool RallyPointController::showPlanFromManagerVehicle (void)
{ {
qCDebug(RallyPointControllerLog) << "showPlanFromManagerVehicle _editMode" << _editMode; qCDebug(RallyPointControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
if (_masterController->offline()) { if (_masterController->offline()) {
qCWarning(RallyPointControllerLog) << "RallyPointController::showPlanFromManagerVehicle called while offline"; qCWarning(RallyPointControllerLog) << "RallyPointController::showPlanFromManagerVehicle called while offline";
return true; // stops further propagation of showPlanFromManagerVehicle due to error return true; // stops further propagation of showPlanFromManagerVehicle due to error
......
...@@ -37,7 +37,7 @@ void SectionTest::init(void) ...@@ -37,7 +37,7 @@ void SectionTest::init(void)
70.1234567, 70.1234567,
true, // autoContinue true, // autoContinue
false); // isCurrentItem false); // isCurrentItem
_simpleItem = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem); _simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this);
} }
void SectionTest::cleanup(void) void SectionTest::cleanup(void)
...@@ -77,13 +77,13 @@ void SectionTest::_commonScanTest(Section* section) ...@@ -77,13 +77,13 @@ void SectionTest::_commonScanTest(Section* section)
QmlObjectListModel waypointVisualItems; QmlObjectListModel waypointVisualItems;
MissionItem waypointItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false); MissionItem waypointItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleItem(_offlineVehicle, true /* editMode */, waypointItem); SimpleMissionItem simpleItem(_offlineVehicle, false /* flyView */, waypointItem, this);
waypointVisualItems.append(&simpleItem); waypointVisualItems.append(&simpleItem);
waypointVisualItems.append(&simpleItem); waypointVisualItems.append(&simpleItem);
waypointVisualItems.append(&simpleItem); waypointVisualItems.append(&simpleItem);
QmlObjectListModel complexVisualItems; QmlObjectListModel complexVisualItems;
SurveyComplexItem surveyItem(_offlineVehicle); SurveyComplexItem surveyItem(_offlineVehicle, false /* fly View */, this);
complexVisualItems.append(&surveyItem); complexVisualItems.append(&surveyItem);
// This tests the common cases which should not lead to scan succeess // This tests the common cases which should not lead to scan succeess
......
...@@ -51,8 +51,8 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = { ...@@ -51,8 +51,8 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = {
{ "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT }, { "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT },
}; };
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent) SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
: VisualMissionItem (vehicle, parent) : VisualMissionItem (vehicle, flyView, parent)
, _rawEdit (false) , _rawEdit (false)
, _dirty (false) , _dirty (false)
, _ignoreDirtyChangeSignals (false) , _ignoreDirtyChangeSignals (false)
...@@ -84,8 +84,8 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent) ...@@ -84,8 +84,8 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
setDirty(false); setDirty(false);
} }
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const MissionItem& missionItem, QObject* parent) SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent)
: VisualMissionItem (vehicle, parent) : VisualMissionItem (vehicle, flyView, parent)
, _missionItem (missionItem) , _missionItem (missionItem)
, _rawEdit (false) , _rawEdit (false)
, _dirty (false) , _dirty (false)
...@@ -130,13 +130,13 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const Miss ...@@ -130,13 +130,13 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const Miss
_altitudeFact.setRawValue(specifiesCoordinate() ? _missionItem._param7Fact.rawValue() : qQNaN()); _altitudeFact.setRawValue(specifiesCoordinate() ? _missionItem._param7Fact.rawValue() : qQNaN());
_amslAltAboveTerrainFact.setRawValue(qQNaN()); _amslAltAboveTerrainFact.setRawValue(qQNaN());
// In !editMode we skip some of the intialization to save memory // In flyView we skip some of the intialization to save memory
if (editMode) { if (!_flyView) {
_setupMetaData(); _setupMetaData();
} }
_connectSignals(); _connectSignals();
_updateOptionalSections(); _updateOptionalSections();
if (editMode) { if (!_flyView) {
_rebuildFacts(); _rebuildFacts();
} }
...@@ -146,8 +146,8 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const Miss ...@@ -146,8 +146,8 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const Miss
setDirty(false); setDirty(false);
} }
SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* parent) SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent)
: VisualMissionItem (other, parent) : VisualMissionItem (other, flyView, parent)
, _missionItem (other._vehicle) , _missionItem (other._vehicle)
, _rawEdit (false) , _rawEdit (false)
, _dirty (false) , _dirty (false)
......
...@@ -23,9 +23,9 @@ class SimpleMissionItem : public VisualMissionItem ...@@ -23,9 +23,9 @@ class SimpleMissionItem : public VisualMissionItem
Q_OBJECT Q_OBJECT
public: public:
SimpleMissionItem(Vehicle* vehicle, QObject* parent = NULL); SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent);
SimpleMissionItem(Vehicle* vehicle, bool editMode, const MissionItem& missionItem, QObject* parent = NULL); SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent);
SimpleMissionItem(const SimpleMissionItem& other, QObject* parent = NULL); SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent);
~SimpleMissionItem(); ~SimpleMissionItem();
......
...@@ -92,7 +92,7 @@ void SimpleMissionItemTest::init(void) ...@@ -92,7 +92,7 @@ void SimpleMissionItemTest::init(void)
70.1234567, 70.1234567,
true, // autoContinue true, // autoContinue
false); // isCurrentItem false); // isCurrentItem
_simpleItem = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem); _simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this);
// It's important top check that the right signals are emitted at the right time since that drives ui change. // It's important top check that the right signals are emitted at the right time since that drives ui change.
// It's also important to check that things are not being over-signalled when they should not be, since that can lead // It's also important to check that things are not being over-signalled when they should not be, since that can lead
...@@ -131,7 +131,7 @@ void SimpleMissionItemTest::_testEditorFacts(void) ...@@ -131,7 +131,7 @@ void SimpleMissionItemTest::_testEditorFacts(void)
70.1234567, 70.1234567,
true, // autoContinue true, // autoContinue
false); // isCurrentItem false); // isCurrentItem
SimpleMissionItem simpleMissionItem(vehicle, true /* editMode */, missionItem); SimpleMissionItem simpleMissionItem(vehicle, false /* flyView */, missionItem, NULL);
// Validate that the fact values are correctly returned // Validate that the fact values are correctly returned
...@@ -167,7 +167,7 @@ void SimpleMissionItemTest::_testEditorFacts(void) ...@@ -167,7 +167,7 @@ void SimpleMissionItemTest::_testEditorFacts(void)
void SimpleMissionItemTest::_testDefaultValues(void) void SimpleMissionItemTest::_testDefaultValues(void)
{ {
SimpleMissionItem item(_offlineVehicle); SimpleMissionItem item(_offlineVehicle, false /* flyView */, NULL);
item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT); item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT); item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
......
...@@ -134,7 +134,7 @@ void SpeedSectionTest::_checkAvailable(void) ...@@ -134,7 +134,7 @@ void SpeedSectionTest::_checkAvailable(void)
70.1234567, 70.1234567,
true, // autoContinue true, // autoContinue
false); // isCurrentItem false); // isCurrentItem
SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem); SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this);
QVERIFY(item->speedSection()); QVERIFY(item->speedSection());
QCOMPARE(item->speedSection()->available(), false); QCOMPARE(item->speedSection()->available(), false);
} }
...@@ -193,7 +193,7 @@ void SpeedSectionTest::_testScanForSection(void) ...@@ -193,7 +193,7 @@ void SpeedSectionTest::_testScanForSection(void)
double flightSpeed = 10.123456; double flightSpeed = 10.123456;
MissionItem validSpeedItem(0, MAV_CMD_DO_CHANGE_SPEED, MAV_FRAME_MISSION, _offlineVehicle->multiRotor() ? 1 : 0, flightSpeed, -1, 0, 0, 0, 0, true, false); MissionItem validSpeedItem(0, MAV_CMD_DO_CHANGE_SPEED, MAV_FRAME_MISSION, _offlineVehicle->multiRotor() ? 1 : 0, flightSpeed, -1, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleItem(_offlineVehicle, true /* editMode */, validSpeedItem); SimpleMissionItem simpleItem(_offlineVehicle, false /* flyView */, validSpeedItem, NULL);
MissionItem& simpleMissionItem = simpleItem.missionItem(); MissionItem& simpleMissionItem = simpleItem.missionItem();
visualItems.append(&simpleItem); visualItems.append(&simpleItem);
scanIndex = 0; scanIndex = 0;
...@@ -263,9 +263,8 @@ void SpeedSectionTest::_testScanForSection(void) ...@@ -263,9 +263,8 @@ void SpeedSectionTest::_testScanForSection(void)
scanIndex = 0; scanIndex = 0;
// Valid item in wrong position // Valid item in wrong position
QmlObjectListModel waypointVisualItems;
MissionItem waypointMissionItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false); MissionItem waypointMissionItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleWaypointItem(_offlineVehicle, true /* editMode */, waypointMissionItem); SimpleMissionItem simpleWaypointItem(_offlineVehicle, false /* flyView */, waypointMissionItem, NULL);
simpleMissionItem = validSpeedItem; simpleMissionItem = validSpeedItem;
visualItems.append(&simpleWaypointItem); visualItems.append(&simpleWaypointItem);
visualItems.append(&simpleMissionItem); visualItems.append(&simpleMissionItem);
......
...@@ -31,8 +31,8 @@ const char* StructureScanComplexItem::_jsonAltitudeRelativeKey = "altitud ...@@ -31,8 +31,8 @@ const char* StructureScanComplexItem::_jsonAltitudeRelativeKey = "altitud
QMap<QString, FactMetaData*> StructureScanComplexItem::_metaDataMap; QMap<QString, FactMetaData*> StructureScanComplexItem::_metaDataMap;
StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* parent) StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyView, QObject* parent)
: ComplexMissionItem (vehicle, parent) : ComplexMissionItem (vehicle, flyView, parent)
, _sequenceNumber (0) , _sequenceNumber (0)
, _dirty (false) , _dirty (false)
, _altitudeRelative (true) , _altitudeRelative (true)
......
...@@ -25,7 +25,7 @@ class StructureScanComplexItem : public ComplexMissionItem ...@@ -25,7 +25,7 @@ class StructureScanComplexItem : public ComplexMissionItem
Q_OBJECT Q_OBJECT
public: public:
StructureScanComplexItem(Vehicle* vehicle, QObject* parent = NULL); StructureScanComplexItem(Vehicle* vehicle, bool flyView, QObject* parent);
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT) Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
Q_PROPERTY(Fact* altitude READ altitude CONSTANT) Q_PROPERTY(Fact* altitude READ altitude CONSTANT)
......
...@@ -24,7 +24,7 @@ void StructureScanComplexItemTest::init(void) ...@@ -24,7 +24,7 @@ void StructureScanComplexItemTest::init(void)
_rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool)); _rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this); _offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_structureScanItem = new StructureScanComplexItem(_offlineVehicle, this); _structureScanItem = new StructureScanComplexItem(_offlineVehicle, false /* flyView */, this);
_structureScanItem->setDirty(false); _structureScanItem->setDirty(false);
_multiSpy = new MultiSignalSpy(); _multiSpy = new MultiSignalSpy();
...@@ -121,7 +121,7 @@ void StructureScanComplexItemTest::_testSaveLoad(void) ...@@ -121,7 +121,7 @@ void StructureScanComplexItemTest::_testSaveLoad(void)
_structureScanItem->save(items); _structureScanItem->save(items);
QString errorString; QString errorString;
StructureScanComplexItem* newItem = new StructureScanComplexItem(_offlineVehicle, this); StructureScanComplexItem* newItem = new StructureScanComplexItem(_offlineVehicle, false /* flyView */, this);
QVERIFY(newItem->load(items[0].toObject(), 10, errorString)); QVERIFY(newItem->load(items[0].toObject(), 10, errorString));
QVERIFY(errorString.isEmpty()); QVERIFY(errorString.isEmpty());
_validateItem(newItem); _validateItem(newItem);
......
...@@ -58,8 +58,8 @@ const char* SurveyComplexItem::_jsonV3FixedValueIsAltitudeKey = "fixedVa ...@@ -58,8 +58,8 @@ const char* SurveyComplexItem::_jsonV3FixedValueIsAltitudeKey = "fixedVa
const char* SurveyComplexItem::_jsonV3Refly90DegreesKey = "refly90Degrees"; const char* SurveyComplexItem::_jsonV3Refly90DegreesKey = "refly90Degrees";
SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, QObject* parent) SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, bool flyView, QObject* parent)
: TransectStyleComplexItem (vehicle, settingsGroup, parent) : TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this)) , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this))
, _gridAngleFact (settingsGroup, _metaDataMap[gridAngleName]) , _gridAngleFact (settingsGroup, _metaDataMap[gridAngleName])
, _gridEntryLocationFact (settingsGroup, _metaDataMap[gridEntryLocationName]) , _gridEntryLocationFact (settingsGroup, _metaDataMap[gridEntryLocationName])
......
...@@ -21,7 +21,7 @@ class SurveyComplexItem : public TransectStyleComplexItem ...@@ -21,7 +21,7 @@ class SurveyComplexItem : public TransectStyleComplexItem
Q_OBJECT Q_OBJECT
public: public:
SurveyComplexItem(Vehicle* vehicle, QObject* parent = NULL); SurveyComplexItem(Vehicle* vehicle, bool flyView, QObject* parent);
Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT) Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT)
Q_PROPERTY(Fact* gridEntryLocation READ gridEntryLocation CONSTANT) Q_PROPERTY(Fact* gridEntryLocation READ gridEntryLocation CONSTANT)
......
...@@ -29,7 +29,7 @@ void SurveyComplexItemTest::init(void) ...@@ -29,7 +29,7 @@ void SurveyComplexItemTest::init(void)
_rgSurveySignals[surveyDirtyChangedIndex] = SIGNAL(dirtyChanged(bool)); _rgSurveySignals[surveyDirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this); _offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_surveyItem = new SurveyComplexItem(_offlineVehicle, this); _surveyItem = new SurveyComplexItem(_offlineVehicle, false /* flyView */, this);
_surveyItem->turnAroundDistance()->setRawValue(0); // Unit test written for no turnaround distance _surveyItem->turnAroundDistance()->setRawValue(0); // Unit test written for no turnaround distance
_surveyItem->setDirty(false); _surveyItem->setDirty(false);
_mapPolygon = _surveyItem->surveyAreaPolygon(); _mapPolygon = _surveyItem->surveyAreaPolygon();
......
...@@ -38,8 +38,8 @@ const char* TransectStyleComplexItem::_jsonFollowTerrainKey = "Fol ...@@ -38,8 +38,8 @@ const char* TransectStyleComplexItem::_jsonFollowTerrainKey = "Fol
const int TransectStyleComplexItem::_terrainQueryTimeoutMsecs = 1000; const int TransectStyleComplexItem::_terrainQueryTimeoutMsecs = 1000;
TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString settingsGroup, QObject* parent) TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, bool flyView, QString settingsGroup, QObject* parent)
: ComplexMissionItem (vehicle, parent) : ComplexMissionItem (vehicle, flyView, parent)
, _settingsGroup (settingsGroup) , _settingsGroup (settingsGroup)
, _sequenceNumber (0) , _sequenceNumber (0)
, _dirty (false) , _dirty (false)
......
...@@ -25,7 +25,7 @@ class TransectStyleComplexItem : public ComplexMissionItem ...@@ -25,7 +25,7 @@ class TransectStyleComplexItem : public ComplexMissionItem
Q_OBJECT Q_OBJECT
public: public:
TransectStyleComplexItem(Vehicle* vehicle, QString settignsGroup, QObject* parent = NULL); TransectStyleComplexItem(Vehicle* vehicle, bool flyView, QString settignsGroup, QObject* parent);
Q_PROPERTY(QGCMapPolygon* surveyAreaPolygon READ surveyAreaPolygon CONSTANT) Q_PROPERTY(QGCMapPolygon* surveyAreaPolygon READ surveyAreaPolygon CONSTANT)
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT) Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
......
...@@ -168,7 +168,7 @@ void TransectStyleComplexItemTest::_adjustSurveAreaPolygon(void) ...@@ -168,7 +168,7 @@ void TransectStyleComplexItemTest::_adjustSurveAreaPolygon(void)
} }
TransectStyleItem::TransectStyleItem(Vehicle* vehicle, QObject* parent) TransectStyleItem::TransectStyleItem(Vehicle* vehicle, QObject* parent)
: TransectStyleComplexItem (vehicle, QStringLiteral("UnitTestTransect"), parent) : TransectStyleComplexItem (vehicle, false /* flyView */, QStringLiteral("UnitTestTransect"), parent)
, rebuildTransectsCalled (false) , rebuildTransectsCalled (false)
{ {
......
...@@ -21,9 +21,10 @@ const char* VisualMissionItem::jsonTypeKey = "type"; ...@@ -21,9 +21,10 @@ const char* VisualMissionItem::jsonTypeKey = "type";
const char* VisualMissionItem::jsonTypeSimpleItemValue = "SimpleItem"; const char* VisualMissionItem::jsonTypeSimpleItemValue = "SimpleItem";
const char* VisualMissionItem::jsonTypeComplexItemValue = "ComplexItem"; const char* VisualMissionItem::jsonTypeComplexItemValue = "ComplexItem";
VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent) VisualMissionItem::VisualMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
: QObject (parent) : QObject (parent)
, _vehicle (vehicle) , _vehicle (vehicle)
, _flyView (flyView)
, _isCurrentItem (false) , _isCurrentItem (false)
, _dirty (false) , _dirty (false)
, _homePositionSpecialCase (false) , _homePositionSpecialCase (false)
...@@ -41,9 +42,10 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent) ...@@ -41,9 +42,10 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent)
_commonInit(); _commonInit();
} }
VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, QObject* parent) VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, bool flyView, QObject* parent)
: QObject (parent) : QObject (parent)
, _vehicle (NULL) , _vehicle (NULL)
, _flyView (flyView)
, _isCurrentItem (false) , _isCurrentItem (false)
, _dirty (false) , _dirty (false)
, _homePositionSpecialCase (false) , _homePositionSpecialCase (false)
...@@ -161,7 +163,7 @@ void VisualMissionItem::setMissionVehicleYaw(double vehicleYaw) ...@@ -161,7 +163,7 @@ void VisualMissionItem::setMissionVehicleYaw(double vehicleYaw)
void VisualMissionItem::_updateTerrainAltitude(void) void VisualMissionItem::_updateTerrainAltitude(void)
{ {
if (coordinate().isValid()) { if (!_flyView && coordinate().isValid()) {
// We use a timer so that any additional requests before the timer fires result in only a single request // We use a timer so that any additional requests before the timer fires result in only a single request
_updateTerrainTimer.start(); _updateTerrainTimer.start();
} }
......
...@@ -33,8 +33,8 @@ class VisualMissionItem : public QObject ...@@ -33,8 +33,8 @@ class VisualMissionItem : public QObject
Q_OBJECT Q_OBJECT
public: public:
VisualMissionItem(Vehicle* vehicle, QObject* parent = NULL); VisualMissionItem(Vehicle* vehicle, bool flyView, QObject* parent);
VisualMissionItem(const VisualMissionItem& other, QObject* parent = NULL); VisualMissionItem(const VisualMissionItem& other, bool flyView, QObject* parent);
~VisualMissionItem(); ~VisualMissionItem();
...@@ -189,6 +189,7 @@ signals: ...@@ -189,6 +189,7 @@ signals:
protected: protected:
Vehicle* _vehicle; Vehicle* _vehicle;
bool _flyView;
bool _isCurrentItem; bool _isCurrentItem;
bool _dirty; bool _dirty;
bool _homePositionSpecialCase; ///< true: This item is being used as a ui home position indicator bool _homePositionSpecialCase; ///< true: This item is being used as a ui home position indicator
......
...@@ -157,7 +157,7 @@ QGCView { ...@@ -157,7 +157,7 @@ QGCView {
id: masterController id: masterController
Component.onCompleted: { Component.onCompleted: {
start(true /* editMode */) start(false /* flyView */)
_missionController.setCurrentPlanViewIndex(0, true) _missionController.setCurrentPlanViewIndex(0, true)
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment