Commit 7fcc3a02 authored by DoinLakeFlyer's avatar DoinLakeFlyer

parent 67b72725
......@@ -592,7 +592,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
// Check for a scan success
SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
newValidGimbalItem->missionItem() = _validGimbalItem->missionItem();
visualItems.append(newValidGimbalItem);
scanIndex = 0;
......@@ -676,7 +676,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
// Check for a scan success
SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
newValidCameraModeItem->missionItem() = _validCameraPhotoModeItem->missionItem();
visualItems.append(newValidCameraModeItem);
scanIndex = 0;
......@@ -735,7 +735,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
Mission Param #3 Number of images to capture total - 0 for unlimited capture
*/
SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
newValidTimeItem->missionItem() = _validTimeItem->missionItem();
visualItems.append(newValidTimeItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
......@@ -776,7 +776,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
Mission Param #7 Empty
*/
SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
newValidDistanceItem->missionItem() = _validDistanceItem->missionItem();
visualItems.append(newValidDistanceItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
......@@ -862,7 +862,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
Mission Param #3 Reserved
*/
SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
newValidStartVideoItem->missionItem() = _validStartVideoItem->missionItem();
visualItems.append(newValidStartVideoItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
......@@ -898,7 +898,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
Mission Param #1 Reserved (Set to 0)
*/
SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
newValidStopVideoItem->missionItem() = _validStopVideoItem->missionItem();
visualItems.append(newValidStopVideoItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
......@@ -936,8 +936,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void)
_commonScanTest(_cameraSection);
SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
newValidStopDistanceItem->missionItem() = _validStopDistanceItem->missionItem();
newValidStopTimeItem->missionItem() = _validStopTimeItem->missionItem();
visualItems.append(newValidStopDistanceItem);
......@@ -950,8 +950,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void)
// Out of order commands
SimpleMissionItem validStopDistanceItem(_offlineVehicle, false /* flyView */, nullptr);
SimpleMissionItem validStopTimeItem(_offlineVehicle, false /* flyView */, nullptr);
SimpleMissionItem validStopDistanceItem(_offlineVehicle, false /* flyView */, false /* forLoad */, nullptr);
SimpleMissionItem validStopTimeItem(_offlineVehicle, false /* flyView */, false /* forLoad */, nullptr);
validStopDistanceItem.missionItem() = _validStopDistanceItem->missionItem();
validStopTimeItem.missionItem() = _validStopTimeItem->missionItem();
visualItems.append(&validStopTimeItem);
......@@ -979,7 +979,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
Mission Param #4 0 Unused sequence id
*/
SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
newValidTakePhotoItem->missionItem() = _validTakePhotoItem->missionItem();
visualItems.append(newValidTakePhotoItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
......@@ -1051,9 +1051,9 @@ void CameraSectionTest::_testScanForMultipleItems(void)
// Camera action followed by gimbal/mode
for (SimpleMissionItem* actionItem: rgActionItems) {
for (SimpleMissionItem* cameraItem: rgCameraItems) {
SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
item1->missionItem() = actionItem->missionItem();
SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1);
visualItems.append(item2);
......@@ -1072,9 +1072,9 @@ void CameraSectionTest::_testScanForMultipleItems(void)
// Gimbal/Mode followed by camera action
for (SimpleMissionItem* actionItem: rgCameraItems) {
for (SimpleMissionItem* cameraItem: rgActionItems) {
SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
item1->missionItem() = actionItem->missionItem();
SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this);
item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1);
visualItems.append(item2);
......
......@@ -97,7 +97,7 @@ void FWLandingPatternTest::_testAppendSectionItems(void)
QmlObjectListModel* simpleItems = new QmlObjectListModel(this);
for (MissionItem* item: rgMissionItems) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, simpleItems);
SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, simpleItems);
simpleItem->missionItem() = *item;
simpleItems->append(simpleItem);
}
......@@ -118,7 +118,7 @@ void FWLandingPatternTest::_testAppendSectionItems(void)
_fwItem->appendMissionItems(rgMissionItems, this);
simpleItems = new QmlObjectListModel(this);
for (MissionItem* item: rgMissionItems) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, simpleItems);
SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, simpleItems);
simpleItem->missionItem() = *item;
simpleItems->append(simpleItem);
}
......
......@@ -359,7 +359,7 @@ int MissionController::_nextSequenceNumber(void)
VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex, bool makeCurrentItem)
{
int sequenceNumber = _nextSequenceNumber();
SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, false /* forLoad */, this);
newItem->setSequenceNumber(sequenceNumber);
newItem->setCoordinate(coordinate);
newItem->setCommand(command);
......@@ -673,7 +673,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
if (json.contains(_jsonPlannedHomePositionKey)) {
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, true /* forLoad */, visualItems);
if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
settingsItem->setInitialHomePositionFromUser(item->coordinate());
item->deleteLater();
......@@ -709,11 +709,11 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
}
const QJsonObject itemObject = itemValue.toObject();
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, true /* forLoad */, visualItems);
if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
if (TakeoffMissionItem::isTakeoffCommand(item->mavCommand())) {
// This needs to be a TakeoffMissionItem
TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, visualItems);
TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, true /* forLoad */, visualItems);
takeoffItem->load(itemObject, itemObject["id"].toInt(), errorString);
item->deleteLater();
item = takeoffItem;
......@@ -797,11 +797,11 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
QString itemType = itemObject[VisualMissionItem::jsonTypeKey].toString();
if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, true /* forLoad */, visualItems);
if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(simpleItem->command()))) {
// This needs to be a TakeoffMissionItem
TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, this);
TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, true /* forLoad */, this);
takeoffItem->load(itemObject, nextSequenceNumber, errorString);
simpleItem->deleteLater();
simpleItem = takeoffItem;
......@@ -941,14 +941,14 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
while (!stream.atEnd()) {
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, true /* forLoad */, visualItems);
if (item->load(stream)) {
if (firstItem && plannedHomePositionInFile) {
settingsItem->setInitialHomePositionFromUser(item->coordinate());
} else {
if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(item->command()))) {
// This needs to be a TakeoffMissionItem
TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, visualItems);
TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, true /* forLoad */, visualItems);
takeoffItem->load(stream);
item->deleteLater();
item = takeoffItem;
......
......@@ -281,7 +281,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void)
{
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, nullptr);
SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, nullptr);
QString testString("10\t0\t3\t80\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n");
QTextStream testStream(&testString, QIODevice::ReadOnly);
......@@ -451,7 +451,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void)
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, nullptr);
SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, nullptr);
QString errorString;
QJsonArray coordinateArray;
QJsonObject jsonObject;
......
......@@ -51,7 +51,7 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = {
{ "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT },
};
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, bool forLoad, QObject* parent)
: VisualMissionItem (vehicle, flyView, parent)
, _rawEdit (false)
, _dirty (false)
......@@ -75,13 +75,15 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* pa
_editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");
_setupMetaData();
if (!forLoad) {
// We are are going to load the SimpleItem right after this then don't connnect up signalling until after load is done
_connectSignals();
_updateOptionalSections();
_setDefaultsForCommand();
_rebuildFacts();
setDirty(false);
}
}
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent)
......@@ -295,7 +297,10 @@ bool SimpleMissionItem::load(QTextStream &loadStream)
_altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
_amslAltAboveTerrainFact.setRawValue(qQNaN());
}
_connectSignals();
_updateOptionalSections();
_rebuildFacts();
setDirty(false);
}
return success;
......@@ -328,7 +333,10 @@ bool SimpleMissionItem::load(const QJsonObject& json, int sequenceNumber, QStrin
}
}
_connectSignals();
_updateOptionalSections();
_rebuildFacts();
setDirty(false);
return true;
}
......
......@@ -24,9 +24,8 @@ class SimpleMissionItem : public VisualMissionItem
Q_OBJECT
public:
SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent);
SimpleMissionItem(Vehicle* vehicle, bool flyView, bool forLoad, QObject* parent);
SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent);
//SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent);
~SimpleMissionItem();
......
......@@ -167,7 +167,7 @@ void SimpleMissionItemTest::_testEditorFacts(void)
void SimpleMissionItemTest::_testDefaultValues(void)
{
SimpleMissionItem item(_offlineVehicle, false /* flyView */, nullptr);
SimpleMissionItem item(_offlineVehicle, false /* flyView */, false /* forLoad */, nullptr);
item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
......
......@@ -19,26 +19,26 @@
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"
TakeoffMissionItem::TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
: SimpleMissionItem (vehicle, flyView, parent)
TakeoffMissionItem::TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, bool forLoad, QObject* parent)
: SimpleMissionItem (vehicle, flyView, forLoad, parent)
, _settingsItem (settingsItem)
{
_init();
_init(forLoad);
}
TakeoffMissionItem::TakeoffMissionItem(MAV_CMD takeoffCmd, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
: SimpleMissionItem (vehicle, flyView, parent)
: SimpleMissionItem (vehicle, flyView, false /* forLoad */, parent)
, _settingsItem (settingsItem)
{
setCommand(takeoffCmd);
_init();
_init(false /* forLoad */);
}
TakeoffMissionItem::TakeoffMissionItem(const MissionItem& missionItem, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
: SimpleMissionItem (vehicle, flyView, missionItem, parent)
, _settingsItem (settingsItem)
{
_init();
_init(false /* forLoad */);
_wizardMode = false;
}
......@@ -47,7 +47,7 @@ TakeoffMissionItem::~TakeoffMissionItem()
}
void TakeoffMissionItem::_init(void)
void TakeoffMissionItem::_init(bool forLoad)
{
_editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");
......@@ -69,6 +69,11 @@ void TakeoffMissionItem::_init(void)
}
}
if (forLoad) {
// Load routines will set the rest up after load
return;
}
_initLaunchTakeoffAtSameLocation();
if (homePosition.isValid() && coordinate().isValid()) {
......
......@@ -19,7 +19,7 @@ class TakeoffMissionItem : public SimpleMissionItem
Q_OBJECT
public:
TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, bool forLoad, QObject* parent);
TakeoffMissionItem(MAV_CMD takeoffCmd, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
TakeoffMissionItem(const MissionItem& missionItem, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
......@@ -55,7 +55,7 @@ signals:
void launchTakeoffAtSameLocationChanged (bool launchTakeoffAtSameLocation);
private:
void _init(void);
void _init(bool forLoad);
void _initLaunchTakeoffAtSameLocation(void);
MissionSettingsItem* _settingsItem;
......
......@@ -498,7 +498,19 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<Te
TransectStyleComplexItem::ReadyForSaveState TransectStyleComplexItem::readyForSaveState(void) const
{
bool terrainReady = _followTerrain ? _transectsPathHeightInfo.count() : true;
bool terrainReady = false;
if (_followTerrain) {
if (_loadedMissionItems.count()) {
// We have loaded mission items. Everything is ready to go.
terrainReady = true;
} else {
// Survey is currently being designed. We aren't ready if we don't have terrain heights yet.
terrainReady = _transectsPathHeightInfo.count();
}
} else {
// Now following terrain so always ready on terrain
terrainReady = true;
}
bool polygonNotReady = !_surveyAreaPolygon.isValid();
return (polygonNotReady || _wizardMode) ?
NotReadyForSaveData :
......
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