Browse Source

Don't query terrain from Fly View

QGC4.4
DonLakeFlyer 7 years ago
parent
commit
4faf39fd2a
  1. 2
      src/FlightDisplay/FlightDisplayView.qml
  2. 68
      src/MissionManager/CameraSectionTest.cc
  3. 4
      src/MissionManager/ComplexMissionItem.cc
  4. 2
      src/MissionManager/ComplexMissionItem.h
  5. 4
      src/MissionManager/CorridorScanComplexItem.cc
  6. 2
      src/MissionManager/CorridorScanComplexItem.h
  7. 2
      src/MissionManager/CorridorScanComplexItemTest.cc
  8. 8
      src/MissionManager/FixedWingLandingComplexItem.cc
  9. 4
      src/MissionManager/FixedWingLandingComplexItem.h
  10. 12
      src/MissionManager/GeoFenceController.cc
  11. 2
      src/MissionManager/GeoFenceController.h
  12. 74
      src/MissionManager/MissionController.cc
  13. 2
      src/MissionManager/MissionController.h
  14. 4
      src/MissionManager/MissionControllerTest.cc
  15. 4
      src/MissionManager/MissionItemTest.cc
  16. 7
      src/MissionManager/MissionSettingsItem.cc
  17. 3
      src/MissionManager/MissionSettingsItem.h
  18. 2
      src/MissionManager/MissionSettingsTest.cc
  19. 12
      src/MissionManager/PlanElementController.cc
  20. 5
      src/MissionManager/PlanElementController.h
  21. 56
      src/MissionManager/PlanMasterController.cc
  22. 5
      src/MissionManager/PlanMasterController.h
  23. 2
      src/MissionManager/PlanMasterControllerTest.cc
  24. 6
      src/MissionManager/RallyPointController.cc
  25. 6
      src/MissionManager/SectionTest.cc
  26. 18
      src/MissionManager/SimpleMissionItem.cc
  27. 6
      src/MissionManager/SimpleMissionItem.h
  28. 6
      src/MissionManager/SimpleMissionItemTest.cc
  29. 7
      src/MissionManager/SpeedSectionTest.cc
  30. 4
      src/MissionManager/StructureScanComplexItem.cc
  31. 2
      src/MissionManager/StructureScanComplexItem.h
  32. 4
      src/MissionManager/StructureScanComplexItemTest.cc
  33. 4
      src/MissionManager/SurveyComplexItem.cc
  34. 2
      src/MissionManager/SurveyComplexItem.h
  35. 2
      src/MissionManager/SurveyComplexItemTest.cc
  36. 4
      src/MissionManager/TransectStyleComplexItem.cc
  37. 2
      src/MissionManager/TransectStyleComplexItem.h
  38. 2
      src/MissionManager/TransectStyleComplexItemTest.cc
  39. 8
      src/MissionManager/VisualMissionItem.cc
  40. 5
      src/MissionManager/VisualMissionItem.h
  41. 2
      src/PlanView/PlanView.qml

2
src/FlightDisplay/FlightDisplayView.qml

@ -109,7 +109,7 @@ QGCView { @@ -109,7 +109,7 @@ QGCView {
PlanMasterController {
id: masterController
Component.onCompleted: start(false /* editMode */)
Component.onCompleted: start(true /* flyView */)
}
Connections {

68
src/MissionManager/CameraSectionTest.cc

@ -46,15 +46,15 @@ void CameraSectionTest::init(void) @@ -46,15 +46,15 @@ void CameraSectionTest::init(void)
QVERIFY(_spySection);
_validGimbalItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
false, // flyView
MissionItem(0, MAV_CMD_DO_MOUNT_CONTROL, MAV_FRAME_MISSION, 10.1234, 0, 20.1234, 0, 0, 0, MAV_MOUNT_MODE_MAVLINK_TARGETING, true, false),
this);
_validTimeItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
false, // flyView
MissionItem(0, MAV_CMD_IMAGE_START_CAPTURE, MAV_FRAME_MISSION, 0, 48, 0, NAN, NAN, NAN, NAN, true, false),
this);
_validDistanceItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
false, // flyView
MissionItem(0,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
@ -65,7 +65,7 @@ void CameraSectionTest::init(void) @@ -65,7 +65,7 @@ void CameraSectionTest::init(void)
true, false),
this);
_validStartVideoItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
false, // flyView
MissionItem(0, // sequence number
MAV_CMD_VIDEO_START_CAPTURE,
MAV_FRAME_MISSION,
@ -76,19 +76,19 @@ void CameraSectionTest::init(void) @@ -76,19 +76,19 @@ void CameraSectionTest::init(void)
false), // isCurrentItem
this);
_validStopVideoItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
false, // flyView
MissionItem(0, MAV_CMD_VIDEO_STOP_CAPTURE, MAV_FRAME_MISSION, 0, NAN, NAN, NAN, NAN, NAN, NAN, true, false),
this);
_validStopDistanceItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
false, // flyView
MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, 0, 0, 0, 0, 0, 0, 0, true, false),
this);
_validStopTimeItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
false, // flyView
MissionItem(1, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_FRAME_MISSION, 0, NAN, NAN, NAN, NAN, NAN, NAN, true, false),
this);
_validCameraPhotoModeItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
false, // flyView
MissionItem(0, // sequence number
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
@ -99,7 +99,7 @@ void CameraSectionTest::init(void) @@ -99,7 +99,7 @@ void CameraSectionTest::init(void)
false), // isCurrentItem
this);
_validCameraVideoModeItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
false, // flyView
MissionItem(0, // sequence number
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
@ -110,7 +110,7 @@ void CameraSectionTest::init(void) @@ -110,7 +110,7 @@ void CameraSectionTest::init(void)
false), // isCurrentItem
this);
_validCameraSurveyPhotoModeItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
false, // flyView
MissionItem(0, // sequence number
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
@ -121,7 +121,7 @@ void CameraSectionTest::init(void) @@ -121,7 +121,7 @@ void CameraSectionTest::init(void)
false), // isCurrentItem
this);
_validTakePhotoItem = new SimpleMissionItem(_offlineVehicle,
true, // editMode
false, // flyView
MissionItem(0,
MAV_CMD_IMAGE_START_CAPTURE,
MAV_FRAME_MISSION,
@ -362,7 +362,7 @@ void CameraSectionTest::_checkAvailable(void) @@ -362,7 +362,7 @@ void CameraSectionTest::_checkAvailable(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem);
SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this);
QVERIFY(item->cameraSection());
QCOMPARE(item->cameraSection()->available(), false);
}
@ -606,7 +606,7 @@ void CameraSectionTest::_testScanForGimbalSection(void) @@ -606,7 +606,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
// Check for a scan success
SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
newValidGimbalItem->missionItem() = _validGimbalItem->missionItem();
visualItems.append(newValidGimbalItem);
scanIndex = 0;
@ -633,7 +633,7 @@ void CameraSectionTest::_testScanForGimbalSection(void) @@ -633,7 +633,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
// Gimbal command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validGimbalItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validGimbalItem->missionItem(), NULL);
invalidSimpleItem.missionItem().setParam2(10); // roll is not supported
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -690,7 +690,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void) @@ -690,7 +690,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
// Check for a scan success
SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
newValidCameraModeItem->missionItem() = _validCameraPhotoModeItem->missionItem();
visualItems.append(newValidCameraModeItem);
scanIndex = 0;
@ -723,7 +723,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void) @@ -723,7 +723,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
*/
// Mode command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validCameraPhotoModeItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validCameraPhotoModeItem->missionItem(), NULL);
invalidSimpleItem.missionItem().setParam3(1); // Param3 should be NaN
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -749,7 +749,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void) @@ -749,7 +749,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
Mission Param #3 Number of images to capture total - 0 for unlimited capture
*/
SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
newValidTimeItem->missionItem() = _validTimeItem->missionItem();
visualItems.append(newValidTimeItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
@ -762,7 +762,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void) @@ -762,7 +762,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
// Image start command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validTimeItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validTimeItem->missionItem(), NULL);
invalidSimpleItem.missionItem().setParam3(10); // must be 0 for unlimited
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -790,7 +790,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) @@ -790,7 +790,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
Mission Param #7 Empty
*/
SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
newValidDistanceItem->missionItem() = _validDistanceItem->missionItem();
visualItems.append(newValidDistanceItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
@ -803,7 +803,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) @@ -803,7 +803,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
// Trigger distance command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validDistanceItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validDistanceItem->missionItem(), NULL);
invalidSimpleItem.missionItem().setParam1(-1); // must be >= 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -876,7 +876,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) @@ -876,7 +876,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
Mission Param #3 Reserved
*/
SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
newValidStartVideoItem->missionItem() = _validStartVideoItem->missionItem();
visualItems.append(newValidStartVideoItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
@ -888,7 +888,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) @@ -888,7 +888,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
// Start Video command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validStartVideoItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validStartVideoItem->missionItem(), NULL);
invalidSimpleItem.missionItem().setParam1(10); // Reserved (must be 0)
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -912,7 +912,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void) @@ -912,7 +912,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
Mission Param #1 Reserved (Set to 0)
*/
SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
newValidStopVideoItem->missionItem() = _validStopVideoItem->missionItem();
visualItems.append(newValidStopVideoItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
@ -924,7 +924,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void) @@ -924,7 +924,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
// Trigger distance command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validStopVideoItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validStopVideoItem->missionItem(), NULL);
invalidSimpleItem.missionItem().setParam1(10); // must be 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -950,8 +950,8 @@ void CameraSectionTest::_testScanForStopImageSection(void) @@ -950,8 +950,8 @@ void CameraSectionTest::_testScanForStopImageSection(void)
_commonScanTest(_cameraSection);
SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
newValidStopDistanceItem->missionItem() = _validStopDistanceItem->missionItem();
newValidStopTimeItem->missionItem() = _validStopTimeItem->missionItem();
visualItems.append(newValidStopDistanceItem);
@ -964,8 +964,8 @@ void CameraSectionTest::_testScanForStopImageSection(void) @@ -964,8 +964,8 @@ void CameraSectionTest::_testScanForStopImageSection(void)
// Out of order commands
SimpleMissionItem validStopDistanceItem(_offlineVehicle);
SimpleMissionItem validStopTimeItem(_offlineVehicle);
SimpleMissionItem validStopDistanceItem(_offlineVehicle, false /* flyView */, NULL);
SimpleMissionItem validStopTimeItem(_offlineVehicle, false /* flyView */, NULL);
validStopDistanceItem.missionItem() = _validStopDistanceItem->missionItem();
validStopTimeItem.missionItem() = _validStopTimeItem->missionItem();
visualItems.append(&validStopTimeItem);
@ -993,7 +993,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void) @@ -993,7 +993,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
Mission Param #4 Reserved
*/
SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
newValidTakePhotoItem->missionItem() = _validTakePhotoItem->missionItem();
visualItems.append(newValidTakePhotoItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
@ -1005,7 +1005,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void) @@ -1005,7 +1005,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
// Take Photo command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, true /* editMode */, _validTimeItem->missionItem());
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validTimeItem->missionItem(), NULL);
invalidSimpleItem.missionItem().setParam3(10); // must be 1 for single photo
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -1065,9 +1065,9 @@ void CameraSectionTest::_testScanForMultipleItems(void) @@ -1065,9 +1065,9 @@ void CameraSectionTest::_testScanForMultipleItems(void)
// Camera action followed by gimbal/mode
foreach (SimpleMissionItem* actionItem, rgActionItems) {
foreach (SimpleMissionItem* cameraItem, rgCameraItems) {
SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
item1->missionItem() = actionItem->missionItem();
SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1);
visualItems.append(item2);
@ -1086,9 +1086,9 @@ void CameraSectionTest::_testScanForMultipleItems(void) @@ -1086,9 +1086,9 @@ void CameraSectionTest::_testScanForMultipleItems(void)
// Gimbal/Mode followed by camera action
foreach (SimpleMissionItem* actionItem, rgCameraItems) {
foreach (SimpleMissionItem* cameraItem, rgActionItems) {
SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
item1->missionItem() = actionItem->missionItem();
SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1);
visualItems.append(item2);

4
src/MissionManager/ComplexMissionItem.cc

@ -11,8 +11,8 @@ @@ -11,8 +11,8 @@
const char* ComplexMissionItem::jsonComplexItemTypeKey = "complexItemType";
ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, QObject* parent)
: VisualMissionItem(vehicle, parent)
ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
: VisualMissionItem(vehicle, flyView, parent)
{
}

2
src/MissionManager/ComplexMissionItem.h

@ -17,7 +17,7 @@ class ComplexMissionItem : public VisualMissionItem @@ -17,7 +17,7 @@ class ComplexMissionItem : public VisualMissionItem
Q_OBJECT
public:
ComplexMissionItem(Vehicle* vehicle, QObject* parent = NULL);
ComplexMissionItem(Vehicle* vehicle, bool flyView, QObject* parent);
const ComplexMissionItem& operator=(const ComplexMissionItem& other);

4
src/MissionManager/CorridorScanComplexItem.cc

@ -27,8 +27,8 @@ const char* CorridorScanComplexItem::_jsonEntryPointKey = "EntryPoint"; @@ -27,8 +27,8 @@ const char* CorridorScanComplexItem::_jsonEntryPointKey = "EntryPoint";
const char* CorridorScanComplexItem::jsonComplexItemTypeValue = "CorridorScan";
CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, QObject* parent)
: TransectStyleComplexItem (vehicle, settingsGroup, parent)
CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, bool flyView, QObject* parent)
: TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent)
, _entryPoint (0)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CorridorScan.SettingsGroup.json"), this))
, _corridorWidthFact (settingsGroup, _metaDataMap[corridorWidthName])

2
src/MissionManager/CorridorScanComplexItem.h

@ -23,7 +23,7 @@ class CorridorScanComplexItem : public TransectStyleComplexItem @@ -23,7 +23,7 @@ class CorridorScanComplexItem : public TransectStyleComplexItem
Q_OBJECT
public:
CorridorScanComplexItem(Vehicle* vehicle, QObject* parent = NULL);
CorridorScanComplexItem(Vehicle* vehicle, bool flyView, QObject* parent);
Q_PROPERTY(QGCMapPolyline* corridorPolyline READ corridorPolyline CONSTANT)
Q_PROPERTY(Fact* corridorWidth READ corridorWidth CONSTANT)

2
src/MissionManager/CorridorScanComplexItemTest.cc

@ -23,7 +23,7 @@ void CorridorScanComplexItemTest::init(void) @@ -23,7 +23,7 @@ void CorridorScanComplexItemTest::init(void)
UnitTest::init();
_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
MissionController::MissionFlightStatus_t missionFlightStatus;

8
src/MissionManager/FixedWingLandingComplexItem.cc

@ -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::_jsonLoiterAltitudeRelativeKey = "loiterAltitudeRelative";
FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObject* parent)
: ComplexMissionItem (vehicle, parent)
FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool flyView, QObject* parent)
: ComplexMissionItem (vehicle, flyView, parent)
, _sequenceNumber (0)
, _dirty (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);
}
bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, Vehicle* vehicle)
bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, bool flyView, Vehicle* vehicle)
{
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
FixedWingLandingComplexItem* complexItem = new FixedWingLandingComplexItem(vehicle, visualItems);
FixedWingLandingComplexItem* complexItem = new FixedWingLandingComplexItem(vehicle, flyView, visualItems);
complexItem->_ignoreRecalcSignals = true;

4
src/MissionManager/FixedWingLandingComplexItem.h

@ -22,7 +22,7 @@ class FixedWingLandingComplexItem : public ComplexMissionItem @@ -22,7 +22,7 @@ class FixedWingLandingComplexItem : public ComplexMissionItem
Q_OBJECT
public:
FixedWingLandingComplexItem(Vehicle* vehicle, QObject* parent = NULL);
FixedWingLandingComplexItem(Vehicle* vehicle, bool flyView, QObject* parent);
Q_PROPERTY(Fact* loiterAltitude READ loiterAltitude CONSTANT)
Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT)
@ -52,7 +52,7 @@ public: @@ -52,7 +52,7 @@ public:
void setLoiterCoordinate (const QGeoCoordinate& coordinate);
/// 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

12
src/MissionManager/GeoFenceController.cc

@ -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();
}
@ -269,7 +269,7 @@ void GeoFenceController::_managerLoadComplete(void) @@ -269,7 +269,7 @@ void GeoFenceController::_managerLoadComplete(void)
{
// Fly view always reloads on _loadComplete
// Plan view only reloads on _loadComplete if specifically requested
if (!_editMode || _itemsRequested) {
if (_flyView || _itemsRequested) {
_setReturnPointFromManager(_geoFenceManager->breachReturnPoint());
_setFenceFromManager(_geoFenceManager->polygons(), _geoFenceManager->circles());
setDirty(false);
@ -282,7 +282,7 @@ void GeoFenceController::_managerLoadComplete(void) @@ -282,7 +282,7 @@ void GeoFenceController::_managerLoadComplete(void)
void GeoFenceController::_managerSendComplete(bool error)
{
// Fly view always reloads on manager sendComplete
if (!error && !_editMode) {
if (!error && _flyView) {
showPlanFromManagerVehicle();
}
}
@ -307,7 +307,7 @@ void GeoFenceController::_updateContainsItems(void) @@ -307,7 +307,7 @@ void GeoFenceController::_updateContainsItems(void)
bool GeoFenceController::showPlanFromManagerVehicle(void)
{
qCDebug(GeoFenceControllerLog) << "showPlanFromManagerVehicle" << _editMode;
qCDebug(GeoFenceControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
if (_masterController->offline()) {
qCWarning(GeoFenceControllerLog) << "GeoFenceController::showPlanFromManagerVehicle called while offline";
return true; // stops further propagation of showPlanFromManagerVehicle due to error

2
src/MissionManager/GeoFenceController.h

@ -62,7 +62,7 @@ public: @@ -62,7 +62,7 @@ public:
// Overrides from PlanElementController
bool supported (void) const final;
void start (bool editMode) final;
void start (bool flyView) final;
void save (QJsonObject& json) final;
bool load (const QJsonObject& json, QString& errorString) final;
void loadFromVehicle (void) final;

74
src/MissionManager/MissionController.cc

@ -123,11 +123,11 @@ void MissionController::_resetMissionFlightStatus(void) @@ -123,11 +123,11 @@ void MissionController::_resetMissionFlightStatus(void)
}
void MissionController::start(bool editMode)
void MissionController::start(bool flyView)
{
qCDebug(MissionControllerLog) << "start editMode" << editMode;
qCDebug(MissionControllerLog) << "start flyView" << flyView;
PlanElementController::start(editMode);
PlanElementController::start(flyView);
_init();
}
@ -146,7 +146,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque @@ -146,7 +146,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
// Fly view always reloads on _loadComplete
// Plan view only reloads on _loadComplete if specifically requested
if (!_editMode || removeAllRequested || _itemsRequested) {
if (_flyView || removeAllRequested || _itemsRequested) {
// Fly Mode (accept if):
// - Always accepts new items from the vehicle so Fly view is kept up to date
// Edit Mode (accept if):
@ -176,7 +176,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque @@ -176,7 +176,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
for (; i<newMissionItems.count(); i++) {
const MissionItem* missionItem = newMissionItems[i];
newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _editMode, *missionItem, this));
newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this));
}
_deinitAllVisualItems();
@ -187,7 +187,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque @@ -187,7 +187,7 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
_visualItems = newControllerMissionItems;
if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
_addMissionSettings(_visualItems, _editMode && _visualItems->count() > 0 /* addToCenter */);
_addMissionSettings(_visualItems, !_flyView && _visualItems->count() > 0 /* addToCenter */);
}
MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
@ -331,7 +331,7 @@ int MissionController::_nextSequenceNumber(void) @@ -331,7 +331,7 @@ int MissionController::_nextSequenceNumber(void)
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
{
int sequenceNumber = _nextSequenceNumber();
SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this);
SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
newItem->setSequenceNumber(sequenceNumber);
newItem->setCoordinate(coordinate);
newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
@ -363,7 +363,7 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i) @@ -363,7 +363,7 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
int sequenceNumber = _nextSequenceNumber();
SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this);
SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
newItem->setSequenceNumber(sequenceNumber);
newItem->setCommand((MAV_CMD)(_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)MAV_CMD_DO_SET_ROI_LOCATION) ?
MAV_CMD_DO_SET_ROI_LOCATION :
@ -393,15 +393,15 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate @@ -393,15 +393,15 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
int sequenceNumber = _nextSequenceNumber();
if (itemName == _surveyMissionItemName) {
newItem = new SurveyComplexItem(_controllerVehicle, _visualItems);
newItem = new SurveyComplexItem(_controllerVehicle, _flyView, _visualItems);
newItem->setCoordinate(mapCenterCoordinate);
surveyStyleItem = true;
} else if (itemName == _fwLandingMissionItemName) {
newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems);
newItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, _visualItems);
} else if (itemName == _structureScanMissionItemName) {
newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems);
newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, _visualItems);
} else if (itemName == _corridorScanMissionItemName) {
newItem = new CorridorScanComplexItem(_controllerVehicle, _visualItems);
newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, _visualItems);
surveyStyleItem = true;
} else {
qWarning() << "Internal error: Unknown complex item:" << itemName;
@ -529,7 +529,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec @@ -529,7 +529,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
return false;
}
SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, visualItems);
SurveyComplexItem* item = new SurveyComplexItem(_controllerVehicle, _flyView, visualItems);
const QJsonObject itemObject = itemValue.toObject();
if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
surveyItems.append(item);
@ -572,7 +572,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec @@ -572,7 +572,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
}
const QJsonObject itemObject = itemValue.toObject();
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
nextSequenceNumber = item->lastSequenceNumber() + 1;
@ -584,10 +584,10 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec @@ -584,10 +584,10 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
} while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
if (json.contains(_jsonPlannedHomePositionKey)) {
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
settingsItem->setCoordinate(item->coordinate());
visualItems->insert(0, settingsItem);
item->deleteLater();
@ -639,7 +639,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -639,7 +639,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
return false;
}
MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _editMode, visualItems);
MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
settingsItem->setCoordinate(homeCoordinate);
visualItems->insert(0, settingsItem);
qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate;
@ -668,7 +668,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -668,7 +668,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
QString itemType = itemObject[VisualMissionItem::jsonTypeKey].toString();
if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, visualItems);
SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
@ -687,7 +687,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -687,7 +687,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
SurveyComplexItem* surveyItem = new SurveyComplexItem(_controllerVehicle, visualItems);
SurveyComplexItem* surveyItem = new SurveyComplexItem(_controllerVehicle, _flyView, visualItems);
if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
@ -696,7 +696,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -696,7 +696,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
visualItems->append(surveyItem);
} else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, visualItems);
FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, _flyView, visualItems);
if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
@ -705,7 +705,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -705,7 +705,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
visualItems->append(landingItem);
} else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, visualItems);
StructureScanComplexItem* structureItem = new StructureScanComplexItem(_controllerVehicle, _flyView, visualItems);
if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
@ -714,7 +714,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -714,7 +714,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
visualItems->append(structureItem);
} else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, visualItems);
CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, visualItems);
if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
@ -723,7 +723,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -723,7 +723,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
visualItems->append(corridorItem);
} else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _editMode, visualItems);
MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
if (!settingsItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
@ -816,7 +816,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM @@ -816,7 +816,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
MissionSettingsItem* settingsItem = visualItems->value<MissionSettingsItem*>(0);
while (!stream.atEnd()) {
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
if (item->load(stream)) {
if (firstItem && plannedHomePositionInFile) {
@ -1080,7 +1080,7 @@ void MissionController::_recalcWaypointLines(void) @@ -1080,7 +1080,7 @@ void MissionController::_recalcWaypointLines(void)
if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) {
firstCoordinateItem = false;
if (lastCoordinateItem != _settingsItem || (homePositionValid && linkStartToHome)) {
if (_editMode) {
if (!_flyView) {
VisualItemPair pair(lastCoordinateItem, item);
_addWaypointLineSegment(old_table, pair);
}
@ -1095,7 +1095,7 @@ void MissionController::_recalcWaypointLines(void) @@ -1095,7 +1095,7 @@ void MissionController::_recalcWaypointLines(void)
}
if (linkEndToHome && lastCoordinateItem != _settingsItem && homePositionValid) {
if (_editMode) {
if (!_flyView) {
VisualItemPair pair(lastCoordinateItem, _settingsItem);
_addWaypointLineSegment(old_table, pair);
} else {
@ -1503,7 +1503,7 @@ void MissionController::_setPlannedHomePositionFromFirstCoordinate(void) @@ -1503,7 +1503,7 @@ void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
void MissionController::_recalcAll(void)
{
if (_editMode) {
if (!_flyView) {
_setPlannedHomePositionFromFirstCoordinate();
}
_recalcSequence();
@ -1521,7 +1521,7 @@ void MissionController::_initAllVisualItems(void) @@ -1521,7 +1521,7 @@ void MissionController::_initAllVisualItems(void)
qWarning() << "First item not MissionSettingsItem";
return;
}
if (_editMode) {
if (!_flyView) {
_settingsItem->setIsCurrentItem(true);
}
@ -1716,7 +1716,7 @@ double MissionController::_normalizeLon(double lon) @@ -1716,7 +1716,7 @@ double MissionController::_normalizeLon(double lon)
/// Add the Mission Settings complex item to the front of the items
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
{
MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _editMode, visualItems);
MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;
@ -1764,7 +1764,7 @@ int MissionController::resumeMissionIndex(void) const @@ -1764,7 +1764,7 @@ int MissionController::resumeMissionIndex(void) const
int resumeIndex = 0;
if (!_editMode) {
if (_flyView) {
resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
// Resume at the item previous to the item we were heading towards
@ -1779,7 +1779,7 @@ int MissionController::resumeMissionIndex(void) const @@ -1779,7 +1779,7 @@ int MissionController::resumeMissionIndex(void) const
int MissionController::currentMissionIndex(void) const
{
if (_editMode) {
if (!_flyView) {
return -1;
} else {
int currentIndex = _missionManager->currentIndex();
@ -1792,7 +1792,7 @@ int MissionController::currentMissionIndex(void) const @@ -1792,7 +1792,7 @@ int MissionController::currentMissionIndex(void) const
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
{
if (!_editMode) {
if (_flyView) {
if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
sequenceNumber++;
}
@ -1825,9 +1825,9 @@ void MissionController::setDirty(bool dirty) @@ -1825,9 +1825,9 @@ void MissionController::setDirty(bool dirty)
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
if (_editMode) {
if (!_flyView) {
// First we look for a Fixed Wing Landing Pattern which is at the end
FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);
FixedWingLandingComplexItem::scanForItem(visualItems, _flyView, vehicle);
}
int scanIndex = 0;
@ -1836,7 +1836,7 @@ void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualIte @@ -1836,7 +1836,7 @@ void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualIte
qCDebug(MissionControllerLog) << "MissionController::_scanForAdditionalSettings count:scanIndex" << visualItems->count() << scanIndex;
if (_editMode) {
if (!_flyView) {
MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
if (settingsItem) {
scanIndex++;
@ -1937,7 +1937,7 @@ void MissionController::_visualItemsDirtyChanged(bool dirty) @@ -1937,7 +1937,7 @@ void MissionController::_visualItemsDirtyChanged(bool dirty)
bool MissionController::showPlanFromManagerVehicle (void)
{
qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode;
qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
if (_masterController->offline()) {
qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
return true; // stops further propagation of showPlanFromManagerVehicle due to error
@ -1963,7 +1963,7 @@ bool MissionController::showPlanFromManagerVehicle (void) @@ -1963,7 +1963,7 @@ bool MissionController::showPlanFromManagerVehicle (void)
void MissionController::_managerSendComplete(bool error)
{
// Fly view always reloads on send complete
if (!error && !_editMode) {
if (!error && _flyView) {
showPlanFromManagerVehicle();
}
}

2
src/MissionManager/MissionController.h

@ -129,7 +129,7 @@ public: @@ -129,7 +129,7 @@ public:
// Overrides from PlanElementController
bool supported (void) const final { return true; }
void start (bool editMode) final;
void start (bool flyView) final;
void save (QJsonObject& json) final;
bool load (const QJsonObject& json, QString& errorString) final;
void loadFromVehicle (void) final;

4
src/MissionManager/MissionControllerTest.cc

@ -59,7 +59,7 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType) @@ -59,7 +59,7 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
Q_CHECK_PTR(_multiSpyMissionController);
QCOMPARE(_multiSpyMissionController->init(_missionController, _rgMissionControllerSignals, _cMissionControllerSignals), true);
_masterController->start(true /* editMode */);
_masterController->start(false /* flyView */);
// All signals should some through on start
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
_missionController = new MissionController();
Q_CHECK_PTR(_missionController);
_missionController->start(true /* editMode */);
_missionController->start(false /* flyView */);
_missionController->insertSimpleMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->visualItems()->count());
// Go online to empty vehicle

4
src/MissionManager/MissionItemTest.cc

@ -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
// 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");
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
// signalling which can affect values.
SimpleMissionItem simpleMissionItem(_offlineVehicle);
SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, NULL);
QString errorString;
QJsonArray coordinateArray;
QJsonObject jsonObject;

7
src/MissionManager/MissionSettingsItem.cc

@ -27,9 +27,8 @@ const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHome @@ -27,9 +27,8 @@ const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHome
QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap;
MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool planView, QObject* parent)
: ComplexMissionItem (vehicle, parent)
, _planView (planView)
MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject* parent)
: ComplexMissionItem (vehicle, flyView, parent)
, _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble)
, _plannedHomePositionFromVehicle (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
{
return _planView ? tr("Planned Home") : tr("H");
return _flyView ? tr("H") : tr("Planned Home");
}

3
src/MissionManager/MissionSettingsItem.h

@ -24,7 +24,7 @@ class MissionSettingsItem : public ComplexMissionItem @@ -24,7 +24,7 @@ class MissionSettingsItem : public ComplexMissionItem
Q_OBJECT
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(bool missionEndRTL READ missionEndRTL WRITE setMissionEndRTL NOTIFY missionEndRTLChanged)
@ -101,7 +101,6 @@ private slots: @@ -101,7 +101,6 @@ private slots:
void _setHomeAltFromTerrain (double terrainAltitude);
private:
bool _planView;
QGeoCoordinate _plannedHomePositionCoordinate; // Does not include altitude
Fact _plannedHomePositionAltitudeFact;
bool _plannedHomePositionFromVehicle;

2
src/MissionManager/MissionSettingsTest.cc

@ -22,7 +22,7 @@ void MissionSettingsTest::init(void) @@ -22,7 +22,7 @@ void MissionSettingsTest::init(void)
{
VisualMissionItemTest::init();
_settingsItem = new MissionSettingsItem(_offlineVehicle, true /* planView */, this);
_settingsItem = new MissionSettingsItem(_offlineVehicle, false /* flyView */, this);
}
void MissionSettingsTest::cleanup(void)

12
src/MissionManager/PlanElementController.cc

@ -15,11 +15,11 @@ @@ -15,11 +15,11 @@
#include "AppSettings.h"
PlanElementController::PlanElementController(PlanMasterController* masterController, QObject* parent)
: QObject(parent)
, _masterController(masterController)
: QObject (parent)
, _masterController (masterController)
, _controllerVehicle(masterController->controllerVehicle())
, _managerVehicle(masterController->managerVehicle())
, _editMode(false)
, _managerVehicle (masterController->managerVehicle())
, _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)

5
src/MissionManager/PlanElementController.h

@ -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
/// 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 editMode);
virtual void start(bool flyView);
virtual void save (QJsonObject& json) = 0;
virtual bool load (const QJsonObject& json, QString& errorString) = 0;
@ -72,7 +71,7 @@ protected: @@ -72,7 +71,7 @@ protected:
PlanMasterController* _masterController;
Vehicle* _controllerVehicle; ///< Offline controller vehicle
Vehicle* _managerVehicle; ///< Either active vehicle or _controllerVehicle if none
bool _editMode;
bool _flyView;
};
#endif

56
src/MissionManager/PlanMasterController.cc

@ -29,20 +29,20 @@ const char* PlanMasterController::_jsonGeoFenceObjectKey = "geoFence"; @@ -29,20 +29,20 @@ const char* PlanMasterController::_jsonGeoFenceObjectKey = "geoFence";
const char* PlanMasterController::_jsonRallyPointsObjectKey = "rallyPoints";
PlanMasterController::PlanMasterController(QObject* parent)
: QObject(parent)
, _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()))
, _managerVehicle(_controllerVehicle)
, _editMode(false)
, _offline(true)
, _missionController(this)
, _geoFenceController(this)
, _rallyPointController(this)
, _loadGeoFence(false)
, _loadRallyPoints(false)
, _sendGeoFence(false)
, _sendRallyPoints(false)
, _syncInProgress(false)
: QObject (parent)
, _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()))
, _managerVehicle (_controllerVehicle)
, _flyView (true)
, _offline (true)
, _missionController (this)
, _geoFenceController (this)
, _rallyPointController (this)
, _loadGeoFence (false)
, _loadRallyPoints (false)
, _sendGeoFence (false)
, _sendRallyPoints (false)
, _syncInProgress (false)
{
connect(&_missionController, &MissionController::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;
_missionController.start(editMode);
_geoFenceController.start(editMode);
_rallyPointController.start(editMode);
_flyView = flyView;
_missionController.start(_flyView);
_geoFenceController.start(_flyView);
_rallyPointController.start(_flyView);
connect(_multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &PlanMasterController::_activeVehicleChanged);
_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)
{
_editMode = false;
_missionController.start(false);
_geoFenceController.start(false);
_rallyPointController.start(false);
_flyView = true;
_missionController.start(_flyView);
_geoFenceController.start(_flyView);
_rallyPointController.start(_flyView);
_activeVehicleChanged(vehicle);
}
@ -132,7 +132,7 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) @@ -132,7 +132,7 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
_geoFenceController.managerVehicleChanged(_managerVehicle);
_rallyPointController.managerVehicleChanged(_managerVehicle);
if (_editMode) {
if (!_flyView) {
if (!offline()) {
// 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
@ -164,7 +164,7 @@ void PlanMasterController::loadFromVehicle(void) @@ -164,7 +164,7 @@ void PlanMasterController::loadFromVehicle(void)
if (offline()) {
qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called while offline";
} else if (!_editMode) {
} else if (_flyView) {
qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called from Fly view";
} else if (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)
{
if (_editMode && _loadGeoFence) {
if (!_flyView && _loadGeoFence) {
_loadGeoFence = false;
_loadRallyPoints = true;
if (_geoFenceController.supported()) {
@ -198,7 +198,7 @@ void PlanMasterController::_loadMissionComplete(void) @@ -198,7 +198,7 @@ void PlanMasterController::_loadMissionComplete(void)
void PlanMasterController::_loadGeoFenceComplete(void)
{
if (_editMode && _loadRallyPoints) {
if (!_flyView && _loadRallyPoints) {
_loadRallyPoints = false;
if (_rallyPointController.supported()) {
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)
{
if (_editMode) {
if (!_flyView) {
_syncInProgress = false;
emit syncInProgressChanged(false);
}

5
src/MissionManager/PlanMasterController.h

@ -46,8 +46,7 @@ public: @@ -46,8 +46,7 @@ public:
Q_PROPERTY(QStringList saveKmlFilters READ saveKmlFilters CONSTANT) ///< File filter list saving KML files
/// 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 editMode);
Q_INVOKABLE void start(bool flyView);
/// Starts the controller using a single static active vehicle. Will not track global active vehicle changes.
Q_INVOKABLE void startStaticActiveVehicle(Vehicle* vehicle);
@ -111,7 +110,7 @@ private: @@ -111,7 +110,7 @@ private:
MultiVehicleManager* _multiVehicleMgr;
Vehicle* _controllerVehicle; ///< Offline controller vehicle
Vehicle* _managerVehicle; ///< Either active vehicle or _controllerVehicle if none
bool _editMode;
bool _flyView;
bool _offline;
MissionController _missionController;
GeoFenceController _geoFenceController;

2
src/MissionManager/PlanMasterControllerTest.cc

@ -27,7 +27,7 @@ void PlanMasterControllerTest::init(void) @@ -27,7 +27,7 @@ void PlanMasterControllerTest::init(void)
UnitTest::init();
_masterController = new PlanMasterController(this);
_masterController->start(true /* editMode */);
_masterController->start(false /* flyView */);
}
void PlanMasterControllerTest::cleanup(void)

6
src/MissionManager/RallyPointController.cc

@ -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
// Plan view only reloads on _loadComplete if specifically requested
if (!_editMode || _itemsRequested) {
if (_flyView || _itemsRequested) {
_points.clearAndDeleteContents();
QObjectList pointList;
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)
{
// Fly view always reloads after send
if (!error && _editMode) {
if (!error && !_flyView) {
showPlanFromManagerVehicle();
}
}
@ -286,7 +286,7 @@ void RallyPointController::_updateContainsItems(void) @@ -286,7 +286,7 @@ void RallyPointController::_updateContainsItems(void)
bool RallyPointController::showPlanFromManagerVehicle (void)
{
qCDebug(RallyPointControllerLog) << "showPlanFromManagerVehicle _editMode" << _editMode;
qCDebug(RallyPointControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
if (_masterController->offline()) {
qCWarning(RallyPointControllerLog) << "RallyPointController::showPlanFromManagerVehicle called while offline";
return true; // stops further propagation of showPlanFromManagerVehicle due to error

6
src/MissionManager/SectionTest.cc

@ -37,7 +37,7 @@ void SectionTest::init(void) @@ -37,7 +37,7 @@ void SectionTest::init(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
_simpleItem = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem);
_simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this);
}
void SectionTest::cleanup(void)
@ -77,13 +77,13 @@ void SectionTest::_commonScanTest(Section* section) @@ -77,13 +77,13 @@ void SectionTest::_commonScanTest(Section* section)
QmlObjectListModel waypointVisualItems;
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);
QmlObjectListModel complexVisualItems;
SurveyComplexItem surveyItem(_offlineVehicle);
SurveyComplexItem surveyItem(_offlineVehicle, false /* fly View */, this);
complexVisualItems.append(&surveyItem);
// This tests the common cases which should not lead to scan succeess

18
src/MissionManager/SimpleMissionItem.cc

@ -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 },
};
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
: VisualMissionItem (vehicle, parent)
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
: VisualMissionItem (vehicle, flyView, parent)
, _rawEdit (false)
, _dirty (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);
}
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const MissionItem& missionItem, QObject* parent)
: VisualMissionItem (vehicle, parent)
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent)
: VisualMissionItem (vehicle, flyView, parent)
, _missionItem (missionItem)
, _rawEdit (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());
_amslAltAboveTerrainFact.setRawValue(qQNaN());
// In !editMode we skip some of the intialization to save memory
if (editMode) {
// In flyView we skip some of the intialization to save memory
if (!_flyView) {
_setupMetaData();
}
_connectSignals();
_updateOptionalSections();
if (editMode) {
if (!_flyView) {
_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);
}
SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* parent)
: VisualMissionItem (other, parent)
SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent)
: VisualMissionItem (other, flyView, parent)
, _missionItem (other._vehicle)
, _rawEdit (false)
, _dirty (false)

6
src/MissionManager/SimpleMissionItem.h

@ -23,9 +23,9 @@ class SimpleMissionItem : public VisualMissionItem @@ -23,9 +23,9 @@ class SimpleMissionItem : public VisualMissionItem
Q_OBJECT
public:
SimpleMissionItem(Vehicle* vehicle, QObject* parent = NULL);
SimpleMissionItem(Vehicle* vehicle, bool editMode, const MissionItem& missionItem, QObject* parent = NULL);
SimpleMissionItem(const SimpleMissionItem& other, QObject* parent = NULL);
SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent);
SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent);
SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent);
~SimpleMissionItem();

6
src/MissionManager/SimpleMissionItemTest.cc

@ -92,7 +92,7 @@ void SimpleMissionItemTest::init(void) @@ -92,7 +92,7 @@ void SimpleMissionItemTest::init(void)
70.1234567,
true, // autoContinue
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 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,
true, // autoContinue
false); // isCurrentItem
SimpleMissionItem simpleMissionItem(vehicle, true /* editMode */, missionItem);
SimpleMissionItem simpleMissionItem(vehicle, false /* flyView */, missionItem, NULL);
// 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)
{
SimpleMissionItem item(_offlineVehicle);
SimpleMissionItem item(_offlineVehicle, false /* flyView */, NULL);
item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);

7
src/MissionManager/SpeedSectionTest.cc

@ -134,7 +134,7 @@ void SpeedSectionTest::_checkAvailable(void) @@ -134,7 +134,7 @@ void SpeedSectionTest::_checkAvailable(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, true /* editMode */, missionItem);
SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this);
QVERIFY(item->speedSection());
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;
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();
visualItems.append(&simpleItem);
scanIndex = 0;
@ -263,9 +263,8 @@ void SpeedSectionTest::_testScanForSection(void) @@ -263,9 +263,8 @@ void SpeedSectionTest::_testScanForSection(void)
scanIndex = 0;
// 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);
SimpleMissionItem simpleWaypointItem(_offlineVehicle, true /* editMode */, waypointMissionItem);
SimpleMissionItem simpleWaypointItem(_offlineVehicle, false /* flyView */, waypointMissionItem, NULL);
simpleMissionItem = validSpeedItem;
visualItems.append(&simpleWaypointItem);
visualItems.append(&simpleMissionItem);

4
src/MissionManager/StructureScanComplexItem.cc

@ -31,8 +31,8 @@ const char* StructureScanComplexItem::_jsonAltitudeRelativeKey = "altitud @@ -31,8 +31,8 @@ const char* StructureScanComplexItem::_jsonAltitudeRelativeKey = "altitud
QMap<QString, FactMetaData*> StructureScanComplexItem::_metaDataMap;
StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* parent)
: ComplexMissionItem (vehicle, parent)
StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyView, QObject* parent)
: ComplexMissionItem (vehicle, flyView, parent)
, _sequenceNumber (0)
, _dirty (false)
, _altitudeRelative (true)

2
src/MissionManager/StructureScanComplexItem.h

@ -25,7 +25,7 @@ class StructureScanComplexItem : public ComplexMissionItem @@ -25,7 +25,7 @@ class StructureScanComplexItem : public ComplexMissionItem
Q_OBJECT
public:
StructureScanComplexItem(Vehicle* vehicle, QObject* parent = NULL);
StructureScanComplexItem(Vehicle* vehicle, bool flyView, QObject* parent);
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
Q_PROPERTY(Fact* altitude READ altitude CONSTANT)

4
src/MissionManager/StructureScanComplexItemTest.cc

@ -24,7 +24,7 @@ void StructureScanComplexItemTest::init(void) @@ -24,7 +24,7 @@ void StructureScanComplexItemTest::init(void)
_rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_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);
_multiSpy = new MultiSignalSpy();
@ -121,7 +121,7 @@ void StructureScanComplexItemTest::_testSaveLoad(void) @@ -121,7 +121,7 @@ void StructureScanComplexItemTest::_testSaveLoad(void)
_structureScanItem->save(items);
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(errorString.isEmpty());
_validateItem(newItem);

4
src/MissionManager/SurveyComplexItem.cc

@ -58,8 +58,8 @@ const char* SurveyComplexItem::_jsonV3FixedValueIsAltitudeKey = "fixedVa @@ -58,8 +58,8 @@ const char* SurveyComplexItem::_jsonV3FixedValueIsAltitudeKey = "fixedVa
const char* SurveyComplexItem::_jsonV3Refly90DegreesKey = "refly90Degrees";
SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, QObject* parent)
: TransectStyleComplexItem (vehicle, settingsGroup, parent)
SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, bool flyView, QObject* parent)
: TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this))
, _gridAngleFact (settingsGroup, _metaDataMap[gridAngleName])
, _gridEntryLocationFact (settingsGroup, _metaDataMap[gridEntryLocationName])

2
src/MissionManager/SurveyComplexItem.h

@ -21,7 +21,7 @@ class SurveyComplexItem : public TransectStyleComplexItem @@ -21,7 +21,7 @@ class SurveyComplexItem : public TransectStyleComplexItem
Q_OBJECT
public:
SurveyComplexItem(Vehicle* vehicle, QObject* parent = NULL);
SurveyComplexItem(Vehicle* vehicle, bool flyView, QObject* parent);
Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT)
Q_PROPERTY(Fact* gridEntryLocation READ gridEntryLocation CONSTANT)

2
src/MissionManager/SurveyComplexItemTest.cc

@ -29,7 +29,7 @@ void SurveyComplexItemTest::init(void) @@ -29,7 +29,7 @@ void SurveyComplexItemTest::init(void)
_rgSurveySignals[surveyDirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_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->setDirty(false);
_mapPolygon = _surveyItem->surveyAreaPolygon();

4
src/MissionManager/TransectStyleComplexItem.cc

@ -38,8 +38,8 @@ const char* TransectStyleComplexItem::_jsonFollowTerrainKey = "Fol @@ -38,8 +38,8 @@ const char* TransectStyleComplexItem::_jsonFollowTerrainKey = "Fol
const int TransectStyleComplexItem::_terrainQueryTimeoutMsecs = 1000;
TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString settingsGroup, QObject* parent)
: ComplexMissionItem (vehicle, parent)
TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, bool flyView, QString settingsGroup, QObject* parent)
: ComplexMissionItem (vehicle, flyView, parent)
, _settingsGroup (settingsGroup)
, _sequenceNumber (0)
, _dirty (false)

2
src/MissionManager/TransectStyleComplexItem.h

@ -25,7 +25,7 @@ class TransectStyleComplexItem : public ComplexMissionItem @@ -25,7 +25,7 @@ class TransectStyleComplexItem : public ComplexMissionItem
Q_OBJECT
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(CameraCalc* cameraCalc READ cameraCalc CONSTANT)

2
src/MissionManager/TransectStyleComplexItemTest.cc

@ -168,7 +168,7 @@ void TransectStyleComplexItemTest::_adjustSurveAreaPolygon(void) @@ -168,7 +168,7 @@ void TransectStyleComplexItemTest::_adjustSurveAreaPolygon(void)
}
TransectStyleItem::TransectStyleItem(Vehicle* vehicle, QObject* parent)
: TransectStyleComplexItem (vehicle, QStringLiteral("UnitTestTransect"), parent)
: TransectStyleComplexItem (vehicle, false /* flyView */, QStringLiteral("UnitTestTransect"), parent)
, rebuildTransectsCalled (false)
{

8
src/MissionManager/VisualMissionItem.cc

@ -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::jsonTypeComplexItemValue = "ComplexItem";
VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent)
VisualMissionItem::VisualMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
: QObject (parent)
, _vehicle (vehicle)
, _flyView (flyView)
, _isCurrentItem (false)
, _dirty (false)
, _homePositionSpecialCase (false)
@ -41,9 +42,10 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent) @@ -41,9 +42,10 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent)
_commonInit();
}
VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, QObject* parent)
VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, bool flyView, QObject* parent)
: QObject (parent)
, _vehicle (NULL)
, _flyView (flyView)
, _isCurrentItem (false)
, _dirty (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)
{
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
_updateTerrainTimer.start();
}

5
src/MissionManager/VisualMissionItem.h

@ -33,8 +33,8 @@ class VisualMissionItem : public QObject @@ -33,8 +33,8 @@ class VisualMissionItem : public QObject
Q_OBJECT
public:
VisualMissionItem(Vehicle* vehicle, QObject* parent = NULL);
VisualMissionItem(const VisualMissionItem& other, QObject* parent = NULL);
VisualMissionItem(Vehicle* vehicle, bool flyView, QObject* parent);
VisualMissionItem(const VisualMissionItem& other, bool flyView, QObject* parent);
~VisualMissionItem();
@ -189,6 +189,7 @@ signals: @@ -189,6 +189,7 @@ signals:
protected:
Vehicle* _vehicle;
bool _flyView;
bool _isCurrentItem;
bool _dirty;
bool _homePositionSpecialCase; ///< true: This item is being used as a ui home position indicator

2
src/PlanView/PlanView.qml

@ -157,7 +157,7 @@ QGCView { @@ -157,7 +157,7 @@ QGCView {
id: masterController
Component.onCompleted: {
start(true /* editMode */)
start(false /* flyView */)
_missionController.setCurrentPlanViewIndex(0, true)
}

Loading…
Cancel
Save