Browse Source

Fix MissionController/VisualMissionItem lifecycle problems

QGC4.4
DonLakeFlyer 4 years ago committed by Don Gagne
parent
commit
3163c61ae2
  1. 5
      src/MissionManager/CameraCalcTest.cc
  2. 148
      src/MissionManager/CameraSectionTest.cc
  3. 12
      src/MissionManager/CameraSectionTest.h
  4. 4
      src/MissionManager/ComplexMissionItem.cc
  5. 2
      src/MissionManager/ComplexMissionItem.h
  6. 4
      src/MissionManager/CorridorScanComplexItem.cc
  7. 2
      src/MissionManager/CorridorScanComplexItem.h
  8. 6
      src/MissionManager/CorridorScanComplexItemTest.cc
  9. 22
      src/MissionManager/FWLandingPatternTest.cc
  10. 4
      src/MissionManager/FixedWingLandingComplexItem.cc
  11. 4
      src/MissionManager/FixedWingLandingComplexItem.h
  12. 6
      src/MissionManager/LandingComplexItem.cc
  13. 4
      src/MissionManager/LandingComplexItem.h
  14. 49
      src/MissionManager/LandingComplexItemTest.cc
  15. 4
      src/MissionManager/LandingComplexItemTest.h
  16. 6
      src/MissionManager/MissionCommandTreeEditorTest.cc
  17. 54
      src/MissionManager/MissionController.cc
  18. 13
      src/MissionManager/MissionControllerTest.cc
  19. 14
      src/MissionManager/MissionControllerTest.h
  20. 7
      src/MissionManager/MissionItemTest.cc
  21. 4
      src/MissionManager/MissionSettingsItem.cc
  22. 2
      src/MissionManager/MissionSettingsItem.h
  23. 2
      src/MissionManager/MissionSettingsTest.cc
  24. 2
      src/MissionManager/PlanMasterController.h
  25. 1
      src/MissionManager/PlanMasterControllerTest.cc
  26. 6
      src/MissionManager/SectionTest.cc
  27. 8
      src/MissionManager/SimpleMissionItem.cc
  28. 4
      src/MissionManager/SimpleMissionItem.h
  29. 24
      src/MissionManager/SimpleMissionItemTest.cc
  30. 6
      src/MissionManager/SpeedSectionTest.cc
  31. 4
      src/MissionManager/StructureScanComplexItem.cc
  32. 2
      src/MissionManager/StructureScanComplexItem.h
  33. 14
      src/MissionManager/StructureScanComplexItemTest.cc
  34. 1
      src/MissionManager/StructureScanComplexItemTest.h
  35. 4
      src/MissionManager/SurveyComplexItem.cc
  36. 2
      src/MissionManager/SurveyComplexItem.h
  37. 21
      src/MissionManager/SurveyComplexItemTest.cc
  38. 12
      src/MissionManager/TakeoffMissionItem.cc
  39. 6
      src/MissionManager/TakeoffMissionItem.h
  40. 4
      src/MissionManager/TransectStyleComplexItem.cc
  41. 2
      src/MissionManager/TransectStyleComplexItem.h
  42. 12
      src/MissionManager/TransectStyleComplexItemTest.cc
  43. 2
      src/MissionManager/TransectStyleComplexItemTest.h
  44. 8
      src/MissionManager/TransectStyleComplexItemTestBase.cc
  45. 4
      src/MissionManager/VTOLLandingComplexItem.cc
  46. 4
      src/MissionManager/VTOLLandingComplexItem.h
  47. 12
      src/MissionManager/VisualMissionItem.cc
  48. 4
      src/MissionManager/VisualMissionItem.h
  49. 6
      src/MissionManager/VisualMissionItemTest.cc

5
src/MissionManager/CameraCalcTest.cc

@ -32,8 +32,13 @@ void CameraCalcTest::init(void) @@ -32,8 +32,13 @@ void CameraCalcTest::init(void)
void CameraCalcTest::cleanup(void)
{
delete _masterController;
delete _cameraCalc;
delete _multiSpy;
_masterController = nullptr;
_cameraCalc = nullptr;
_multiSpy = nullptr;
}
void CameraCalcTest::_testDirty(void)

148
src/MissionManager/CameraSectionTest.cc

@ -25,19 +25,17 @@ CameraSectionTest::CameraSectionTest(void) @@ -25,19 +25,17 @@ CameraSectionTest::CameraSectionTest(void)
, _validCameraPhotoModeItem (nullptr)
, _validCameraVideoModeItem (nullptr)
, _validCameraSurveyPhotoModeItem (nullptr)
{
{
rgCameraSignals[specifyGimbalChangedIndex] = SIGNAL(specifyGimbalChanged(bool));
rgCameraSignals[specifiedGimbalYawChangedIndex] = SIGNAL(specifiedGimbalYawChanged(double));
rgCameraSignals[specifiedGimbalPitchChangedIndex] = SIGNAL(specifiedGimbalPitchChanged(double));
rgCameraSignals[specifyCameraModeChangedIndex] = SIGNAL(specifyCameraModeChanged(bool));
}
void CameraSectionTest::init(void)
{
SectionTest::init();
rgCameraSignals[specifyGimbalChangedIndex] = SIGNAL(specifyGimbalChanged(bool));
rgCameraSignals[specifiedGimbalYawChangedIndex] = SIGNAL(specifiedGimbalYawChanged(double));
rgCameraSignals[specifiedGimbalPitchChangedIndex] = SIGNAL(specifiedGimbalPitchChanged(double));
rgCameraSignals[specifyCameraModeChangedIndex] = SIGNAL(specifyCameraModeChanged(bool));
_cameraSection = _simpleItem->cameraSection();
_createSpy(_cameraSection, &_spyCamera);
QVERIFY(_spyCamera);
@ -52,8 +50,7 @@ void CameraSectionTest::init(void) @@ -52,8 +50,7 @@ void CameraSectionTest::init(void)
10.1234, 0, 20.1234, // pitch, roll, yaw
0, 0, 0, // alt, lat, lon (all 0 since unused)
MAV_MOUNT_MODE_MAVLINK_TARGETING, // control gimbal with pitch, roll, yaw settings
true, false),
this);
true, false));
_validTimeItem = new SimpleMissionItem(_masterController,
false, // flyView
MissionItem(0,
@ -63,8 +60,7 @@ void CameraSectionTest::init(void) @@ -63,8 +60,7 @@ void CameraSectionTest::init(void)
48, // time interval
0, // 0 = capture forever
NAN, NAN, NAN, NAN, // Reserved
true, false),
this);
true, false));
_validDistanceItem = new SimpleMissionItem(_masterController,
false, // flyView
MissionItem(0,
@ -74,8 +70,7 @@ void CameraSectionTest::init(void) @@ -74,8 +70,7 @@ void CameraSectionTest::init(void)
0, // not shutter integration
1, // trigger immediately
0, 0, 0, 0,
true, false),
this);
true, false));
_validStartVideoItem = new SimpleMissionItem(_masterController,
false, // flyView
MissionItem(0, // sequence number
@ -85,8 +80,7 @@ void CameraSectionTest::init(void) @@ -85,8 +80,7 @@ void CameraSectionTest::init(void)
VIDEO_CAPTURE_STATUS_INTERVAL, // CAMERA_CAPTURE_STATUS (default to every 5 seconds)
NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved
true, // autocontinue
false), // isCurrentItem
this);
false)); // isCurrentItem
_validCameraPhotoModeItem = new SimpleMissionItem(_masterController,
false, // flyView
MissionItem(0, // sequence number
@ -96,8 +90,7 @@ void CameraSectionTest::init(void) @@ -96,8 +90,7 @@ void CameraSectionTest::init(void)
CAMERA_MODE_IMAGE,
NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved
true, // autocontinue
false), // isCurrentItem
this);
false)); // isCurrentItem
_validCameraVideoModeItem = new SimpleMissionItem(_masterController,
false, // flyView
MissionItem(0, // sequence number
@ -107,8 +100,7 @@ void CameraSectionTest::init(void) @@ -107,8 +100,7 @@ void CameraSectionTest::init(void)
CAMERA_MODE_VIDEO,
NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved
true, // autocontinue
false), // isCurrentItem
this);
false)); // isCurrentItem
_validCameraSurveyPhotoModeItem = new SimpleMissionItem(_masterController,
false, // flyView
MissionItem(0, // sequence number
@ -118,8 +110,7 @@ void CameraSectionTest::init(void) @@ -118,8 +110,7 @@ void CameraSectionTest::init(void)
CAMERA_MODE_IMAGE_SURVEY,
NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved
true, // autocontinue
false), // isCurrentItem
this);
false)); // isCurrentItem
_validTakePhotoItem = new SimpleMissionItem(_masterController,
false, // flyView
MissionItem(0,
@ -131,30 +122,36 @@ void CameraSectionTest::init(void) @@ -131,30 +122,36 @@ void CameraSectionTest::init(void)
0, // Sequence id not used
NAN, NAN, NAN, // param 5-7 reserved
true, // autoContinue
false), // isCurrentItem
this);
false)); // isCurrentItem
_validStopVideoItem = createValidStopVideoItem(_masterController, this);
_validStopDistanceItem = createValidStopDistanceItem(_masterController, this);
_validStopTimeItem = createValidStopTimeItem(_masterController, this);
_validStopVideoItem = createValidStopVideoItem(_masterController);
_validStopDistanceItem = createValidStopDistanceItem(_masterController);
_validStopTimeItem = createValidStopTimeItem(_masterController);
}
void CameraSectionTest::cleanup(void)
{
_spyCamera->deleteLater();
_spySection->deleteLater();
_validGimbalItem->deleteLater();
_validDistanceItem->deleteLater();
_validTimeItem->deleteLater();
_validStartVideoItem->deleteLater();
_validStopVideoItem->deleteLater();
_validStopDistanceItem->deleteLater();
_validStopTimeItem->deleteLater();
_validTakePhotoItem->deleteLater();
_validCameraPhotoModeItem->deleteLater();
_validCameraVideoModeItem->deleteLater();
_validCameraSurveyPhotoModeItem->deleteLater();
delete _spyCamera;
delete _spySection;
_spyCamera = nullptr;
_spySection = nullptr;
_cameraSection = nullptr;
SectionTest::cleanup();
// Deletion of _masterController will delete these obects
_validGimbalItem = nullptr;
_validDistanceItem = nullptr;
_validTimeItem = nullptr;
_validStartVideoItem = nullptr;
_validStopVideoItem = nullptr;
_validStopDistanceItem = nullptr;
_validStopTimeItem = nullptr;
_validTakePhotoItem = nullptr;
_validCameraPhotoModeItem = nullptr;
_validCameraVideoModeItem = nullptr;
_validCameraSurveyPhotoModeItem = nullptr;
}
void CameraSectionTest::_createSpy(CameraSection* cameraSection, MultiSignalSpy** cameraSpy)
@ -367,7 +364,7 @@ void CameraSectionTest::_checkAvailable(void) @@ -367,7 +364,7 @@ void CameraSectionTest::_checkAvailable(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
SimpleMissionItem* item = new SimpleMissionItem(_masterController, false /* flyView */, missionItem, this);
SimpleMissionItem* item = new SimpleMissionItem(_masterController, false /* flyView */, missionItem);
QVERIFY(item->cameraSection());
QCOMPARE(item->cameraSection()->available(), false);
}
@ -607,7 +604,7 @@ void CameraSectionTest::_testScanForGimbalSection(void) @@ -607,7 +604,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
// Check for a scan success
SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
newValidGimbalItem->missionItem() = _validGimbalItem->missionItem();
visualItems.append(newValidGimbalItem);
scanIndex = 0;
@ -634,7 +631,7 @@ void CameraSectionTest::_testScanForGimbalSection(void) @@ -634,7 +631,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
// Gimbal command but incorrect settings
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validGimbalItem->missionItem(), nullptr);
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validGimbalItem->missionItem());
invalidSimpleItem.missionItem().setParam2(10); // roll is not supported, should be 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -691,7 +688,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void) @@ -691,7 +688,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
// Check for a scan success
SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
newValidCameraModeItem->missionItem() = _validCameraPhotoModeItem->missionItem();
visualItems.append(newValidCameraModeItem);
scanIndex = 0;
@ -725,7 +722,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void) @@ -725,7 +722,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
// Mode command but incorrect settings
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validCameraPhotoModeItem->missionItem(), nullptr);
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validCameraPhotoModeItem->missionItem());
std::function<void(MissionItem&, double)> rgSetParamFns[] = {
&MissionItem::setParam1,
&MissionItem::setParam2,
@ -763,7 +760,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void) @@ -763,7 +760,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
Mission Param #3 Number of images to capture total - 0 for unlimited capture
*/
SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
newValidTimeItem->missionItem() = _validTimeItem->missionItem();
visualItems.append(newValidTimeItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
@ -776,7 +773,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void) @@ -776,7 +773,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
// Image start command but incorrect settings
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validTimeItem->missionItem(), nullptr);
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validTimeItem->missionItem());
invalidSimpleItem.missionItem().setParam3(10); // must be 0 for unlimited
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -804,7 +801,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) @@ -804,7 +801,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
Mission Param #7 Empty
*/
SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
newValidDistanceItem->missionItem() = _validDistanceItem->missionItem();
visualItems.append(newValidDistanceItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
@ -817,7 +814,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) @@ -817,7 +814,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
// Trigger distance command but incorrect settings
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validDistanceItem->missionItem(), nullptr);
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validDistanceItem->missionItem());
invalidSimpleItem.missionItem().setParam1(-1); // must be >= 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -890,7 +887,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) @@ -890,7 +887,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
Mission Param #3 Reserved
*/
SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
newValidStartVideoItem->missionItem() = _validStartVideoItem->missionItem();
visualItems.append(newValidStartVideoItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
@ -902,7 +899,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) @@ -902,7 +899,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
// Start Video command but incorrect settings
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validStartVideoItem->missionItem(), nullptr);
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validStartVideoItem->missionItem());
invalidSimpleItem.missionItem().setParam1(10); // Reserved (must be 0)
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -926,7 +923,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void) @@ -926,7 +923,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
Mission Param #1 Reserved (Set to 0)
*/
SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
newValidStopVideoItem->missionItem() = _validStopVideoItem->missionItem();
visualItems.append(newValidStopVideoItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
@ -938,7 +935,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void) @@ -938,7 +935,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
// Trigger distance command but incorrect settings
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validStopVideoItem->missionItem(), nullptr);
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validStopVideoItem->missionItem());
invalidSimpleItem.missionItem().setParam1(10); // must be 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -964,8 +961,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void) @@ -964,8 +961,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void)
_commonScanTest(_cameraSection);
SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
newValidStopDistanceItem->missionItem() = _validStopDistanceItem->missionItem();
newValidStopTimeItem->missionItem() = _validStopTimeItem->missionItem();
visualItems.append(newValidStopDistanceItem);
@ -978,8 +975,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void) @@ -978,8 +975,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void)
// Out of order commands
SimpleMissionItem validStopDistanceItem(_masterController, false /* flyView */, false /* forLoad */, nullptr);
SimpleMissionItem validStopTimeItem(_masterController, false /* flyView */, false /* forLoad */, nullptr);
SimpleMissionItem validStopDistanceItem(_masterController, false /* flyView */, false /* forLoad */);
SimpleMissionItem validStopTimeItem(_masterController, false /* flyView */, false /* forLoad */);
validStopDistanceItem.missionItem() = _validStopDistanceItem->missionItem();
validStopTimeItem.missionItem() = _validStopTimeItem->missionItem();
visualItems.append(&validStopTimeItem);
@ -1007,7 +1004,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void) @@ -1007,7 +1004,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
Mission Param #4 0 Unused sequence id
*/
SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
newValidTakePhotoItem->missionItem() = _validTakePhotoItem->missionItem();
visualItems.append(newValidTakePhotoItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
@ -1019,7 +1016,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void) @@ -1019,7 +1016,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
// Take Photo command but incorrect settings
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validTimeItem->missionItem(), nullptr);
SimpleMissionItem invalidSimpleItem(_masterController, false /* flyView */, _validTimeItem->missionItem());
invalidSimpleItem.missionItem().setParam3(10); // must be 1 for single photo
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
@ -1079,9 +1076,9 @@ void CameraSectionTest::_testScanForMultipleItems(void) @@ -1079,9 +1076,9 @@ void CameraSectionTest::_testScanForMultipleItems(void)
// Camera action followed by gimbal/mode
for (SimpleMissionItem* actionItem: rgActionItems) {
for (SimpleMissionItem* cameraItem: rgCameraItems) {
SimpleMissionItem* item1 = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* item1 = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
item1->missionItem() = actionItem->missionItem();
SimpleMissionItem* item2 = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* item2 = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1);
visualItems.append(item2);
@ -1100,9 +1097,9 @@ void CameraSectionTest::_testScanForMultipleItems(void) @@ -1100,9 +1097,9 @@ void CameraSectionTest::_testScanForMultipleItems(void)
// Gimbal/Mode followed by camera action
for (SimpleMissionItem* actionItem: rgCameraItems) {
for (SimpleMissionItem* cameraItem: rgActionItems) {
SimpleMissionItem* item1 = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* item1 = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
item1->missionItem() = actionItem->missionItem();
SimpleMissionItem* item2 = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* item2 = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1);
visualItems.append(item2);
@ -1139,49 +1136,46 @@ void CameraSectionTest::_testSpecifiedGimbalValuesChanged(void) @@ -1139,49 +1136,46 @@ void CameraSectionTest::_testSpecifiedGimbalValuesChanged(void)
QVERIFY(_spyCamera->checkSignalByMask(specifiedGimbalPitchChangedMask));
}
SimpleMissionItem* CameraSectionTest::createValidStopVideoItem(PlanMasterController* masterController, QObject* parent)
SimpleMissionItem* CameraSectionTest::createValidStopVideoItem(PlanMasterController* masterController)
{
return new SimpleMissionItem(masterController,
false, // flyView
MissionItem(0, MAV_CMD_VIDEO_STOP_CAPTURE, MAV_FRAME_MISSION, 0, qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), true, false),
parent);
MissionItem(0, MAV_CMD_VIDEO_STOP_CAPTURE, MAV_FRAME_MISSION, 0, qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), true, false));
}
SimpleMissionItem* CameraSectionTest::createValidStopDistanceItem(PlanMasterController* masterController, QObject* parent)
SimpleMissionItem* CameraSectionTest::createValidStopDistanceItem(PlanMasterController* masterController)
{
return new SimpleMissionItem(masterController,
false, // flyView
MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, 0, 0, 0, 0, 0, 0, 0, true, false),
parent);
MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, 0, 0, 0, 0, 0, 0, 0, true, false));
}
SimpleMissionItem* CameraSectionTest::createValidStopTimeItem(PlanMasterController* masterController, QObject* parent)
SimpleMissionItem* CameraSectionTest::createValidStopTimeItem(PlanMasterController* masterController)
{
return new SimpleMissionItem(masterController,
false, // flyView
MissionItem(1, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_FRAME_MISSION, 0, qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), true, false),
parent);
MissionItem(1, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_FRAME_MISSION, 0, qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), true, false));
}
SimpleMissionItem* CameraSectionTest::createInvalidStopVideoItem(PlanMasterController* masterController, QObject* parent)
SimpleMissionItem* CameraSectionTest::createInvalidStopVideoItem(PlanMasterController* masterController)
{
SimpleMissionItem* invalidSimpleItem = createValidStopVideoItem(masterController, parent);
SimpleMissionItem* invalidSimpleItem = createValidStopVideoItem(masterController);
invalidSimpleItem->missionItem().setParam1(10); // must be 0 to be valid for scan
return invalidSimpleItem;
}
SimpleMissionItem* CameraSectionTest::createInvalidStopDistanceItem(PlanMasterController* masterController, QObject* parent)
SimpleMissionItem* CameraSectionTest::createInvalidStopDistanceItem(PlanMasterController* masterController)
{
SimpleMissionItem* invalidSimpleItem = createValidStopDistanceItem(masterController, parent);
SimpleMissionItem* invalidSimpleItem = createValidStopDistanceItem(masterController);
invalidSimpleItem->missionItem().setParam2(-1); // Should be 0
return invalidSimpleItem;
}
SimpleMissionItem* CameraSectionTest::createInvalidStopTimeItem(PlanMasterController* masterController, QObject* parent)
SimpleMissionItem* CameraSectionTest::createInvalidStopTimeItem(PlanMasterController* masterController)
{
SimpleMissionItem* invalidSimpleItem = createValidStopTimeItem(masterController, parent);
SimpleMissionItem* invalidSimpleItem = createValidStopTimeItem(masterController);
invalidSimpleItem->missionItem().setParam1(1); // Should be 0
return invalidSimpleItem;
}

12
src/MissionManager/CameraSectionTest.h

@ -24,12 +24,12 @@ public: @@ -24,12 +24,12 @@ public:
void init(void) override;
void cleanup(void) override;
static SimpleMissionItem* createValidStopVideoItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createValidStopDistanceItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createValidStopTimeItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createInvalidStopVideoItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createInvalidStopDistanceItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createInvalidStopTimeItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createValidStopVideoItem (PlanMasterController* masterController);
static SimpleMissionItem* createValidStopDistanceItem (PlanMasterController* masterController);
static SimpleMissionItem* createValidStopTimeItem (PlanMasterController* masterController);
static SimpleMissionItem* createInvalidStopVideoItem (PlanMasterController* masterController);
static SimpleMissionItem* createInvalidStopDistanceItem (PlanMasterController* masterController);
static SimpleMissionItem* createInvalidStopTimeItem (PlanMasterController* masterController);
private slots:
void _testDirty (void);

4
src/MissionManager/ComplexMissionItem.cc

@ -22,8 +22,8 @@ const char* ComplexMissionItem::jsonComplexItemTypeKey = "complexItemType"; @@ -22,8 +22,8 @@ const char* ComplexMissionItem::jsonComplexItemTypeKey = "complexItemType";
const char* ComplexMissionItem::_presetSettingsKey = "_presets";
ComplexMissionItem::ComplexMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: VisualMissionItem (masterController, flyView, parent)
ComplexMissionItem::ComplexMissionItem(PlanMasterController* masterController, bool flyView)
: VisualMissionItem (masterController, flyView)
, _toolbox (qgcApp()->toolbox())
, _settingsManager (_toolbox->settingsManager())
{

2
src/MissionManager/ComplexMissionItem.h

@ -27,7 +27,7 @@ class ComplexMissionItem : public VisualMissionItem @@ -27,7 +27,7 @@ class ComplexMissionItem : public VisualMissionItem
Q_OBJECT
public:
ComplexMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent);
ComplexMissionItem(PlanMasterController* masterController, bool flyView);
const ComplexMissionItem& operator=(const ComplexMissionItem& other);

4
src/MissionManager/CorridorScanComplexItem.cc

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

2
src/MissionManager/CorridorScanComplexItem.h

@ -25,7 +25,7 @@ class CorridorScanComplexItem : public TransectStyleComplexItem @@ -25,7 +25,7 @@ class CorridorScanComplexItem : public TransectStyleComplexItem
public:
/// @param flyView true: Created for use in the Fly View, false: Created for use in the Plan View
/// @param kmlFile Polyline comes from this file, empty for default polyline
CorridorScanComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlFile, QObject* parent);
CorridorScanComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlFile);
Q_PROPERTY(QGCMapPolyline* corridorPolyline READ corridorPolyline CONSTANT)
Q_PROPERTY(Fact* corridorWidth READ corridorWidth CONSTANT)

6
src/MissionManager/CorridorScanComplexItemTest.cc

@ -21,7 +21,7 @@ void CorridorScanComplexItemTest::init(void) @@ -21,7 +21,7 @@ void CorridorScanComplexItemTest::init(void)
{
TransectStyleComplexItemTestBase::init();
_corridorItem = new CorridorScanComplexItem(_masterController, false /* flyView */, QString() /* kmlFile */, this /* parent */);
_corridorItem = new CorridorScanComplexItem(_masterController, false /* flyView */, QString() /* kmlFile */);
_corridorItem->corridorPolyline()->appendVertices(_polyLineVertices);
// Setup for expected transect count
@ -42,8 +42,10 @@ void CorridorScanComplexItemTest::init(void) @@ -42,8 +42,10 @@ void CorridorScanComplexItemTest::init(void)
void CorridorScanComplexItemTest::cleanup(void)
{
delete _corridorItem;
TransectStyleComplexItemTestBase::cleanup();
// _corridorItem is deleted when _masterController goes away
_corridorItem = nullptr;
}
void CorridorScanComplexItemTest::_testDirty(void)

22
src/MissionManager/FWLandingPatternTest.cc

@ -22,7 +22,7 @@ void FWLandingPatternTest::init(void) @@ -22,7 +22,7 @@ void FWLandingPatternTest::init(void)
{
VisualMissionItemTest::init();
_fwItem = new FixedWingLandingComplexItem(_masterController, false /* flyView */, this);
_fwItem = new FixedWingLandingComplexItem(_masterController, false /* flyView */);
_createSpy(_fwItem, &_viSpy);
// Start in a clean state
@ -32,19 +32,23 @@ void FWLandingPatternTest::init(void) @@ -32,19 +32,23 @@ void FWLandingPatternTest::init(void)
QVERIFY(!_fwItem->dirty());
_viSpy->clearAllSignals();
_validStopVideoItem = CameraSectionTest::createValidStopTimeItem(_masterController, this);
_validStopDistanceItem = CameraSectionTest::createValidStopTimeItem(_masterController, this);
_validStopTimeItem = CameraSectionTest::createValidStopTimeItem(_masterController, this);
_validStopVideoItem = CameraSectionTest::createValidStopTimeItem(_masterController);
_validStopDistanceItem = CameraSectionTest::createValidStopTimeItem(_masterController);
_validStopTimeItem = CameraSectionTest::createValidStopTimeItem(_masterController);
}
void FWLandingPatternTest::cleanup(void)
{
delete _fwItem;
delete _viSpy;
delete _validStopVideoItem;
delete _validStopDistanceItem;
delete _validStopTimeItem;
_viSpy = nullptr;
VisualMissionItemTest::cleanup();
// These items go away when _masterController goes away
_fwItem = nullptr;
_validStopVideoItem = nullptr;
_validStopDistanceItem = nullptr;
_validStopTimeItem = nullptr;
}
@ -86,7 +90,7 @@ void FWLandingPatternTest::_testSaveLoad(void) @@ -86,7 +90,7 @@ void FWLandingPatternTest::_testSaveLoad(void)
_fwItem->save(items);
QString errorString;
FixedWingLandingComplexItem* newItem = new FixedWingLandingComplexItem(_masterController, false /* flyView */, this /* parent */);
FixedWingLandingComplexItem* newItem = new FixedWingLandingComplexItem(_masterController, false /* flyView */);
bool success =newItem->load(items[0].toObject(), 10, errorString);
if (!success) {
qDebug() << errorString;

4
src/MissionManager/FixedWingLandingComplexItem.cc

@ -29,8 +29,8 @@ const char* FixedWingLandingComplexItem::valueSetIsDistanceName = "V @@ -29,8 +29,8 @@ const char* FixedWingLandingComplexItem::valueSetIsDistanceName = "V
const char* FixedWingLandingComplexItem::_jsonValueSetIsDistanceKey = "valueSetIsDistance";
FixedWingLandingComplexItem::FixedWingLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: LandingComplexItem (masterController, flyView, parent)
FixedWingLandingComplexItem::FixedWingLandingComplexItem(PlanMasterController* masterController, bool flyView)
: LandingComplexItem (masterController, flyView)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/FWLandingPattern.FactMetaData.json"), this))
, _landingDistanceFact (settingsGroup, _metaDataMap[finalApproachToLandDistanceName])
, _finalApproachAltitudeFact(settingsGroup, _metaDataMap[finalApproachAltitudeName])

4
src/MissionManager/FixedWingLandingComplexItem.h

@ -25,7 +25,7 @@ class FixedWingLandingComplexItem : public LandingComplexItem @@ -25,7 +25,7 @@ class FixedWingLandingComplexItem : public LandingComplexItem
Q_OBJECT
public:
FixedWingLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent);
FixedWingLandingComplexItem(PlanMasterController* masterController, bool flyView);
Q_PROPERTY(Fact* valueSetIsDistance READ valueSetIsDistance CONSTANT)
Q_PROPERTY(Fact* glideSlope READ glideSlope CONSTANT)
@ -59,7 +59,7 @@ private slots: @@ -59,7 +59,7 @@ private slots:
void _glideSlopeChanged (void);
private:
static LandingComplexItem* _createItem (PlanMasterController* masterController, bool flyView, QObject* parent) { return new FixedWingLandingComplexItem(masterController, flyView, parent); }
static LandingComplexItem* _createItem (PlanMasterController* masterController, bool flyView) { return new FixedWingLandingComplexItem(masterController, flyView); }
static bool _isValidLandItem(const MissionItem& missionItem);
// Overrides from LandingComplexItem

6
src/MissionManager/LandingComplexItem.cc

@ -50,8 +50,8 @@ const char* LandingComplexItem::_jsonDeprecatedLoiterAltitudeRelativeKey = "l @@ -50,8 +50,8 @@ const char* LandingComplexItem::_jsonDeprecatedLoiterAltitudeRelativeKey = "l
// the new support for using either a loiter or just a waypoint as the approach entry point.
const char* LandingComplexItem::_jsonDeprecatedLoiterCoordinateKey = "loiterCoordinate";
LandingComplexItem::LandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: ComplexMissionItem (masterController, flyView, parent)
LandingComplexItem::LandingComplexItem(PlanMasterController* masterController, bool flyView)
: ComplexMissionItem (masterController, flyView)
{
_isIncomplete = false;
@ -475,7 +475,7 @@ bool LandingComplexItem::_scanForItem(QmlObjectListModel* visualItems, bool flyV @@ -475,7 +475,7 @@ bool LandingComplexItem::_scanForItem(QmlObjectListModel* visualItems, bool flyV
// Now stuff all the scanned information into the item
LandingComplexItem* complexItem = createItemFunc(masterController, flyView, visualItems /* parent */);
LandingComplexItem* complexItem = createItemFunc(masterController, flyView);
complexItem->_ignoreRecalcSignals = true;

4
src/MissionManager/LandingComplexItem.h

@ -25,7 +25,7 @@ class LandingComplexItem : public ComplexMissionItem @@ -25,7 +25,7 @@ class LandingComplexItem : public ComplexMissionItem
Q_OBJECT
public:
LandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent);
LandingComplexItem(PlanMasterController* masterController, bool flyView);
Q_PROPERTY(Fact* finalApproachAltitude READ finalApproachAltitude CONSTANT)
Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT)
@ -153,7 +153,7 @@ protected: @@ -153,7 +153,7 @@ protected:
bool _load (const QJsonObject& complexObject, int sequenceNumber, const QString& jsonComplexItemTypeValue, bool useDeprecatedRelAltKeys, QString& errorString);
typedef bool (*IsLandItemFunc)(const MissionItem& missionItem);
typedef LandingComplexItem* (*CreateItemFunc)(PlanMasterController* masterController, bool flyView, QObject* parent);
typedef LandingComplexItem* (*CreateItemFunc)(PlanMasterController* masterController, bool flyView);
static bool _scanForItem(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController, IsLandItemFunc isLandItemFunc, CreateItemFunc createItemFunc);

49
src/MissionManager/LandingComplexItemTest.cc

@ -18,15 +18,20 @@ const char* SimpleLandingComplexItem::settingsGroup = "SimpleLanding @@ -18,15 +18,20 @@ const char* SimpleLandingComplexItem::settingsGroup = "SimpleLanding
const char* SimpleLandingComplexItem::jsonComplexItemTypeValue = "utSimpleLandingPattern";
LandingComplexItemTest::LandingComplexItemTest(void)
{
{
rgSignals[finalApproachCoordinateChangedIndex] = SIGNAL(finalApproachCoordinateChanged(QGeoCoordinate));
rgSignals[loiterTangentCoordinateChangedIndex] = SIGNAL(loiterTangentCoordinateChanged(QGeoCoordinate));
rgSignals[landingCoordinateChangedIndex] = SIGNAL(landingCoordinateChanged(QGeoCoordinate));
rgSignals[landingCoordSetChangedIndex] = SIGNAL(landingCoordSetChanged(bool));
rgSignals[altitudesAreRelativeChangedIndex] = SIGNAL(altitudesAreRelativeChanged(bool));
rgSignals[_updateFlightPathSegmentsSignalIndex] = SIGNAL(_updateFlightPathSegmentsSignal());
}
void LandingComplexItemTest::init(void)
{
VisualMissionItemTest::init();
_item = new SimpleLandingComplexItem(_masterController, false /* flyView */, this);
_item = new SimpleLandingComplexItem(_masterController, false /* flyView */);
// Start in a clean state
QVERIFY(!_item->dirty());
@ -36,28 +41,26 @@ void LandingComplexItemTest::init(void) @@ -36,28 +41,26 @@ void LandingComplexItemTest::init(void)
VisualMissionItemTest::_createSpy(_item, &_viMultiSpy);
rgSignals[finalApproachCoordinateChangedIndex] = SIGNAL(finalApproachCoordinateChanged(QGeoCoordinate));
rgSignals[loiterTangentCoordinateChangedIndex] = SIGNAL(loiterTangentCoordinateChanged(QGeoCoordinate));
rgSignals[landingCoordinateChangedIndex] = SIGNAL(landingCoordinateChanged(QGeoCoordinate));
rgSignals[landingCoordSetChangedIndex] = SIGNAL(landingCoordSetChanged(bool));
rgSignals[altitudesAreRelativeChangedIndex] = SIGNAL(altitudesAreRelativeChanged(bool));
rgSignals[_updateFlightPathSegmentsSignalIndex] = SIGNAL(_updateFlightPathSegmentsSignal());
_multiSpy = new MultiSignalSpy();
QCOMPARE(_multiSpy->init(_item, rgSignals, cSignals), true);
_validStopVideoItem = CameraSectionTest::createValidStopTimeItem(_masterController, this);
_validStopDistanceItem = CameraSectionTest::createValidStopTimeItem(_masterController, this);
_validStopTimeItem = CameraSectionTest::createValidStopTimeItem(_masterController, this);
_validStopVideoItem = CameraSectionTest::createValidStopTimeItem(_masterController);
_validStopDistanceItem = CameraSectionTest::createValidStopTimeItem(_masterController);
_validStopTimeItem = CameraSectionTest::createValidStopTimeItem(_masterController);
}
void LandingComplexItemTest::cleanup(void)
{
delete _multiSpy;
delete _validStopVideoItem;
delete _validStopDistanceItem;
delete _validStopTimeItem;
_multiSpy = nullptr;
VisualMissionItemTest::cleanup();
// These items go away when _masterController is deleted
_item = nullptr;
_validStopVideoItem = nullptr;
_validStopDistanceItem = nullptr;
_validStopTimeItem = nullptr;
}
void LandingComplexItemTest::_testDirty(void)
@ -185,7 +188,7 @@ void LandingComplexItemTest::_testAppendSectionItems(void) @@ -185,7 +188,7 @@ void LandingComplexItemTest::_testAppendSectionItems(void)
// Convert to simple visual items for verification
QmlObjectListModel* simpleItems = new QmlObjectListModel(this);
for (MissionItem* item: rgMissionItems) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, simpleItems);
SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
simpleItem->missionItem() = *item;
simpleItems->append(simpleItem);
}
@ -236,7 +239,7 @@ void LandingComplexItemTest::_testScanForItems(void) @@ -236,7 +239,7 @@ void LandingComplexItemTest::_testScanForItems(void)
// Convert to simple visual items for _scan
QmlObjectListModel* visualItems = new QmlObjectListModel(this);
for (MissionItem* item: rgMissionItems) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, visualItems);
SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
simpleItem->missionItem() = *item;
visualItems->append(simpleItem);
}
@ -263,7 +266,7 @@ void LandingComplexItemTest::_testSaveLoad(void) @@ -263,7 +266,7 @@ void LandingComplexItemTest::_testSaveLoad(void)
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = SimpleLandingComplexItem::jsonComplexItemTypeValue;
// Test useDeprecatedRelAltKeys = false
SimpleLandingComplexItem* newItem = new SimpleLandingComplexItem(_masterController, false /* flyView */, this /* parent */);
SimpleLandingComplexItem* newItem = new SimpleLandingComplexItem(_masterController, false /* flyView */);
bool loadSuccess = newItem->_load(saveObject, 0 /* sequenceNumber */, SimpleLandingComplexItem::jsonComplexItemTypeValue, false /* useDeprecatedRelAltKeys */, errorString);
if (!loadSuccess) {
qDebug() << "_load failed" << errorString;
@ -278,7 +281,7 @@ void LandingComplexItemTest::_testSaveLoad(void) @@ -278,7 +281,7 @@ void LandingComplexItemTest::_testSaveLoad(void)
saveObject[LandingComplexItem::_jsonDeprecatedLoiterAltitudeRelativeKey] = relAlt;
saveObject[LandingComplexItem::_jsonDeprecatedLandingAltitudeRelativeKey] = relAlt;
saveObject.remove(LandingComplexItem::_jsonAltitudesAreRelativeKey);
newItem = new SimpleLandingComplexItem(_masterController, false /* flyView */, this /* parent */);
newItem = new SimpleLandingComplexItem(_masterController, false /* flyView */);
loadSuccess = newItem->_load(saveObject, 0 /* sequenceNumber */, SimpleLandingComplexItem::jsonComplexItemTypeValue, true /* useDeprecatedRelAltKeys */, errorString);
if (!loadSuccess) {
qDebug() << "_load failed" << errorString;
@ -295,7 +298,7 @@ void LandingComplexItemTest::_testSaveLoad(void) @@ -295,7 +298,7 @@ void LandingComplexItemTest::_testSaveLoad(void)
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = SimpleLandingComplexItem::jsonComplexItemTypeValue;
saveObject[LandingComplexItem::_jsonDeprecatedLoiterCoordinateKey] = saveObject[LandingComplexItem::_jsonFinalApproachCoordinateKey];
saveObject.remove(LandingComplexItem::_jsonFinalApproachCoordinateKey);
newItem = new SimpleLandingComplexItem(_masterController, false /* flyView */, this /* parent */);
newItem = new SimpleLandingComplexItem(_masterController, false /* flyView */);
loadSuccess = newItem->_load(saveObject, 0 /* sequenceNumber */, SimpleLandingComplexItem::jsonComplexItemTypeValue, false /* useDeprecatedRelAltKeys */, errorString);
if (!loadSuccess) {
qDebug() << "_load failed" << errorString;
@ -329,8 +332,8 @@ void LandingComplexItemTest::_validateItem(LandingComplexItem* actualItem, Landi @@ -329,8 +332,8 @@ void LandingComplexItemTest::_validateItem(LandingComplexItem* actualItem, Landi
}
}
SimpleLandingComplexItem::SimpleLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: LandingComplexItem (masterController, flyView, parent)
SimpleLandingComplexItem::SimpleLandingComplexItem(PlanMasterController* masterController, bool flyView)
: LandingComplexItem (masterController, flyView)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/VTOLLandingPattern.FactMetaData.json"), this))
, _landingDistanceFact (settingsGroup, _metaDataMap[finalApproachToLandDistanceName])
, _finalApproachAltitudeFact(settingsGroup, _metaDataMap[finalApproachAltitudeName])

4
src/MissionManager/LandingComplexItemTest.h

@ -70,7 +70,7 @@ class SimpleLandingComplexItem : public LandingComplexItem @@ -70,7 +70,7 @@ class SimpleLandingComplexItem : public LandingComplexItem
Q_OBJECT
public:
SimpleLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent);
SimpleLandingComplexItem(PlanMasterController* masterController, bool flyView);
// Overrides from ComplexMissionItem
QString patternName (void) const final { return QString(); }
@ -90,7 +90,7 @@ private slots: @@ -90,7 +90,7 @@ private slots:
void _updateFlightPathSegmentsDontCallDirectly(void) override;
private:
static LandingComplexItem* _createItem (PlanMasterController* masterController, bool flyView, QObject* parent) { return new SimpleLandingComplexItem(masterController, flyView, parent); }
static LandingComplexItem* _createItem (PlanMasterController* masterController, bool flyView) { return new SimpleLandingComplexItem(masterController, flyView); }
static bool _isValidLandItem(const MissionItem& missionItem);
// Overrides from LandingComplexItem

6
src/MissionManager/MissionCommandTreeEditorTest.cc

@ -26,7 +26,7 @@ void MissionCommandTreeEditorTest::_testEditorsWorker(QGCMAVLink::FirmwareClass_ @@ -26,7 +26,7 @@ void MissionCommandTreeEditorTest::_testEditorsWorker(QGCMAVLink::FirmwareClass_
AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
appSettings->offlineEditingFirmwareClass()->setRawValue(firmwareClass);
appSettings->offlineEditingVehicleClass()->setRawValue(vehicleClass);
PlanMasterController* masterController = new PlanMasterController();
PlanMasterController masterController;
FirmwarePlugin* firmwarePlugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(QGCMAVLink::firmwareClassToAutopilot(firmwareClass), QGCMAVLink::vehicleClassToMavType(vehicleClass));
if (firmwarePlugin->supportedMissionCommands(vehicleClass).count() == 0) {
@ -36,13 +36,13 @@ void MissionCommandTreeEditorTest::_testEditorsWorker(QGCMAVLink::FirmwareClass_ @@ -36,13 +36,13 @@ void MissionCommandTreeEditorTest::_testEditorsWorker(QGCMAVLink::FirmwareClass_
QVariantList varSimpleItems;
for (MAV_CMD command: firmwarePlugin->supportedMissionCommands(vehicleClass)) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(masterController, false /* flyView */, false /* forLoad */, this);
SimpleMissionItem* simpleItem = new SimpleMissionItem(&masterController, false /* flyView */, false /* forLoad */);
simpleItem->setCommand(command);
varSimpleItems.append(QVariant::fromValue(simpleItem));
}
QQmlApplicationEngine* qmlAppEngine = qgcApp()->toolbox()->corePlugin()->createQmlApplicationEngine(this);
qmlAppEngine->rootContext()->setContextProperty("planMasterController", masterController);
qmlAppEngine->rootContext()->setContextProperty("planMasterController", &masterController);
qmlAppEngine->rootContext()->setContextProperty("missionItems", varSimpleItems);
qmlAppEngine->rootContext()->setContextProperty("cColumns", cColumns);
qmlAppEngine->rootContext()->setContextProperty("imagePath", QStringLiteral("/home/parallels/Downloads/%1-%2.png").arg(firmwareClassString).arg(vehicleClassString));

54
src/MissionManager/MissionController.cc

@ -190,10 +190,10 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque @@ -190,10 +190,10 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
for (; i < newMissionItems.count(); i++) {
const MissionItem* missionItem = newMissionItems[i];
SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, _flyView, *missionItem, this);
SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, _flyView, *missionItem);
if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(simpleItem->command()))) {
// This needs to be a TakeoffMissionItem
_takeoffMissionItem = new TakeoffMissionItem(*missionItem, _masterController, _flyView, settingsItem, this);
_takeoffMissionItem = new TakeoffMissionItem(*missionItem, _masterController, _flyView, settingsItem);
simpleItem->deleteLater();
simpleItem = _takeoffMissionItem;
}
@ -312,7 +312,7 @@ int MissionController::_nextSequenceNumber(void) @@ -312,7 +312,7 @@ int MissionController::_nextSequenceNumber(void)
VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex, bool makeCurrentItem)
{
int sequenceNumber = _nextSequenceNumber();
SimpleMissionItem * newItem = new SimpleMissionItem(_masterController, _flyView, false /* forLoad */, this);
SimpleMissionItem * newItem = new SimpleMissionItem(_masterController, _flyView, false /* forLoad */);
newItem->setSequenceNumber(sequenceNumber);
newItem->setCoordinate(coordinate);
newItem->setCommand(command);
@ -359,7 +359,7 @@ VisualMissionItem* MissionController::insertSimpleMissionItem(QGeoCoordinate coo @@ -359,7 +359,7 @@ VisualMissionItem* MissionController::insertSimpleMissionItem(QGeoCoordinate coo
VisualMissionItem* MissionController::insertTakeoffItem(QGeoCoordinate /*coordinate*/, int visualItemIndex, bool makeCurrentItem)
{
int sequenceNumber = _nextSequenceNumber();
_takeoffMissionItem = new TakeoffMissionItem(_controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF, _masterController, _flyView, _settingsItem, this);
_takeoffMissionItem = new TakeoffMissionItem(_controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF, _masterController, _flyView, _settingsItem);
_takeoffMissionItem->setSequenceNumber(sequenceNumber);
_initVisualItem(_takeoffMissionItem);
@ -431,7 +431,7 @@ VisualMissionItem* MissionController::insertComplexMissionItem(QString itemName, @@ -431,7 +431,7 @@ VisualMissionItem* MissionController::insertComplexMissionItem(QString itemName,
ComplexMissionItem* newItem = nullptr;
if (itemName == SurveyComplexItem::name) {
newItem = new SurveyComplexItem(_masterController, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
newItem = new SurveyComplexItem(_masterController, _flyView, QString() /* kmlFile */);
newItem->setCoordinate(mapCenterCoordinate);
double prevAltitude;
@ -443,13 +443,13 @@ VisualMissionItem* MissionController::insertComplexMissionItem(QString itemName, @@ -443,13 +443,13 @@ VisualMissionItem* MissionController::insertComplexMissionItem(QString itemName,
}
}
} else if (itemName == FixedWingLandingComplexItem::name) {
newItem = new FixedWingLandingComplexItem(_masterController, _flyView, _visualItems /* parent */);
newItem = new FixedWingLandingComplexItem(_masterController, _flyView);
} else if (itemName == VTOLLandingComplexItem::name) {
newItem = new VTOLLandingComplexItem(_masterController, _flyView, _visualItems /* parent */);
newItem = new VTOLLandingComplexItem(_masterController, _flyView);
} else if (itemName == StructureScanComplexItem::name) {
newItem = new StructureScanComplexItem(_masterController, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
newItem = new StructureScanComplexItem(_masterController, _flyView, QString() /* kmlFile */);
} else if (itemName == CorridorScanComplexItem::name) {
newItem = new CorridorScanComplexItem(_masterController, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
newItem = new CorridorScanComplexItem(_masterController, _flyView, QString() /* kmlFile */);
} else {
qWarning() << "Internal error: Unknown complex item:" << itemName;
return nullptr;
@ -465,11 +465,11 @@ VisualMissionItem* MissionController::insertComplexMissionItemFromKMLOrSHP(QStri @@ -465,11 +465,11 @@ VisualMissionItem* MissionController::insertComplexMissionItemFromKMLOrSHP(QStri
ComplexMissionItem* newItem = nullptr;
if (itemName == SurveyComplexItem::name) {
newItem = new SurveyComplexItem(_masterController, _flyView, file, _visualItems);
newItem = new SurveyComplexItem(_masterController, _flyView, file);
} else if (itemName == StructureScanComplexItem::name) {
newItem = new StructureScanComplexItem(_masterController, _flyView, file, _visualItems);
newItem = new StructureScanComplexItem(_masterController, _flyView, file);
} else if (itemName == CorridorScanComplexItem::name) {
newItem = new CorridorScanComplexItem(_masterController, _flyView, file, _visualItems);
newItem = new CorridorScanComplexItem(_masterController, _flyView, file);
} else {
qWarning() << "Internal error: Unknown complex item:" << itemName;
return nullptr;
@ -641,7 +641,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec @@ -641,7 +641,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
return false;
}
SurveyComplexItem* item = new SurveyComplexItem(_masterController, _flyView, QString() /* kmlFile */, visualItems /* parent */);
SurveyComplexItem* item = new SurveyComplexItem(_masterController, _flyView, QString() /* kmlFile */);
const QJsonObject itemObject = itemValue.toObject();
if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
surveyItems.append(item);
@ -659,7 +659,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec @@ -659,7 +659,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
if (json.contains(_jsonPlannedHomePositionKey)) {
SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */, visualItems);
SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */);
if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
settingsItem->setInitialHomePositionFromUser(item->coordinate());
item->deleteLater();
@ -695,11 +695,11 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec @@ -695,11 +695,11 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
}
const QJsonObject itemObject = itemValue.toObject();
SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */, visualItems);
SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */);
if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
if (TakeoffMissionItem::isTakeoffCommand(item->mavCommand())) {
// This needs to be a TakeoffMissionItem
TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, true /* forLoad */, visualItems);
TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, true /* forLoad */);
takeoffItem->load(itemObject, itemObject["id"].toInt(), errorString);
item->deleteLater();
item = takeoffItem;
@ -772,7 +772,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -772,7 +772,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
return false;
}
MissionSettingsItem* settingsItem = new MissionSettingsItem(_masterController, _flyView, visualItems);
MissionSettingsItem* settingsItem = new MissionSettingsItem(_masterController, _flyView);
settingsItem->setCoordinate(homeCoordinate);
visualItems->insert(0, settingsItem);
qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate;
@ -801,11 +801,11 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -801,11 +801,11 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
QString itemType = itemObject[VisualMissionItem::jsonTypeKey].toString();
if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */, visualItems);
SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */);
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(_masterController, _flyView, settingsItem, true /* forLoad */, this);
TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, true /* forLoad */);
takeoffItem->load(itemObject, nextSequenceNumber, errorString);
simpleItem->deleteLater();
simpleItem = takeoffItem;
@ -827,7 +827,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -827,7 +827,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
SurveyComplexItem* surveyItem = new SurveyComplexItem(_masterController, _flyView, QString() /* kmlFile */, visualItems);
SurveyComplexItem* surveyItem = new SurveyComplexItem(_masterController, _flyView, QString() /* kmlFile */);
if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
@ -836,7 +836,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -836,7 +836,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(_masterController, _flyView, visualItems);
FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_masterController, _flyView);
if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
@ -845,7 +845,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -845,7 +845,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
visualItems->append(landingItem);
} else if (complexItemType == VTOLLandingComplexItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading VTOL Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
VTOLLandingComplexItem* landingItem = new VTOLLandingComplexItem(_masterController, _flyView, visualItems);
VTOLLandingComplexItem* landingItem = new VTOLLandingComplexItem(_masterController, _flyView);
if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
@ -854,7 +854,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -854,7 +854,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(_masterController, _flyView, QString() /* kmlFile */, visualItems);
StructureScanComplexItem* structureItem = new StructureScanComplexItem(_masterController, _flyView, QString() /* kmlFile */);
if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
@ -863,7 +863,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec @@ -863,7 +863,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(_masterController, _flyView, QString() /* kmlFile */, visualItems);
CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_masterController, _flyView, QString() /* kmlFile */);
if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) {
return false;
}
@ -954,14 +954,14 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM @@ -954,14 +954,14 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
while (!stream.atEnd()) {
SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */, visualItems);
SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */);
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(_masterController, _flyView, settingsItem, true /* forLoad */, visualItems);
TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, true /* forLoad */);
takeoffItem->load(stream);
item->deleteLater();
item = takeoffItem;
@ -2068,7 +2068,7 @@ MissionSettingsItem* MissionController::_addMissionSettings(QmlObjectListModel* @@ -2068,7 +2068,7 @@ MissionSettingsItem* MissionController::_addMissionSettings(QmlObjectListModel*
{
qCDebug(MissionControllerLog) << "_addMissionSettings";
MissionSettingsItem* settingsItem = new MissionSettingsItem(_masterController, _flyView, visualItems);
MissionSettingsItem* settingsItem = new MissionSettingsItem(_masterController, _flyView);
visualItems->insert(0, settingsItem);
if (visualItems == _visualItems) {

13
src/MissionManager/MissionControllerTest.cc

@ -18,9 +18,6 @@ @@ -18,9 +18,6 @@
#include "AppSettings.h"
MissionControllerTest::MissionControllerTest(void)
: _multiSpyMissionController(nullptr)
, _multiSpyMissionItem(nullptr)
, _missionController(nullptr)
{
}
@ -28,13 +25,13 @@ MissionControllerTest::MissionControllerTest(void) @@ -28,13 +25,13 @@ MissionControllerTest::MissionControllerTest(void)
void MissionControllerTest::cleanup(void)
{
delete _masterController;
_masterController = nullptr;
delete _multiSpyMissionController;
_multiSpyMissionController = nullptr;
delete _multiSpyMissionItem;
_multiSpyMissionItem = nullptr;
_masterController = nullptr;
_missionController = nullptr;
_multiSpyMissionController = nullptr;
_multiSpyMissionItem = nullptr;
MissionControllerManagerTest::cleanup();
}

14
src/MissionManager/MissionControllerTest.h

@ -77,16 +77,16 @@ private: @@ -77,16 +77,16 @@ private:
visualItemsChangedSignalMask = 1 << visualItemsChangedSignalIndex,
};
MultiSignalSpy* _multiSpyMissionController;
static const size_t _cMissionControllerSignals = missionControllerMaxSignalIndex;
const char* _rgMissionControllerSignals[_cMissionControllerSignals];
MultiSignalSpy* _multiSpyMissionController = nullptr;
MultiSignalSpy* _multiSpyMissionItem = nullptr;
PlanMasterController* _masterController = nullptr;
MissionController* _missionController = nullptr;
MultiSignalSpy* _multiSpyMissionItem;
static const size_t _cVisualItemSignals = visualItemMaxSignalIndex;
const char* _rgVisualItemSignals[_cVisualItemSignals];
static const size_t _cMissionControllerSignals = missionControllerMaxSignalIndex;
PlanMasterController* _masterController;
MissionController* _missionController;
const char* _rgMissionControllerSignals[_cMissionControllerSignals];
const char* _rgVisualItemSignals[_cVisualItemSignals];
};
#endif

7
src/MissionManager/MissionItemTest.cc

@ -40,7 +40,8 @@ void MissionItemTest::init(void) @@ -40,7 +40,8 @@ void MissionItemTest::init(void)
void MissionItemTest::cleanup(void)
{
_masterController->deleteLater();
delete _masterController;
_masterController = nullptr;
UnitTest::cleanup();
}
@ -278,7 +279,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void) @@ -278,7 +279,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void)
{
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
SimpleMissionItem simpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, nullptr);
SimpleMissionItem simpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
QString testString("10\t0\t3\t80\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n");
QTextStream testStream(&testString, QIODevice::ReadOnly);
@ -448,7 +449,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void) @@ -448,7 +449,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void)
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
SimpleMissionItem simpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, nullptr);
SimpleMissionItem simpleMissionItem(_masterController, false /* flyView */, false /* forLoad */);
QString errorString;
QJsonArray coordinateArray;
QJsonObject jsonObject;

4
src/MissionManager/MissionSettingsItem.cc

@ -25,8 +25,8 @@ const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHome @@ -25,8 +25,8 @@ const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHome
QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap;
MissionSettingsItem::MissionSettingsItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: ComplexMissionItem (masterController, flyView, parent)
MissionSettingsItem::MissionSettingsItem(PlanMasterController* masterController, bool flyView)
: ComplexMissionItem (masterController, flyView)
, _managerVehicle (masterController->managerVehicle())
, _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble)
, _cameraSection (masterController)

2
src/MissionManager/MissionSettingsItem.h

@ -26,7 +26,7 @@ class MissionSettingsItem : public ComplexMissionItem @@ -26,7 +26,7 @@ class MissionSettingsItem : public ComplexMissionItem
Q_OBJECT
public:
MissionSettingsItem(PlanMasterController* masterController, bool flyView, QObject* parent);
MissionSettingsItem(PlanMasterController* masterController, bool flyView);
Q_PROPERTY(Fact* plannedHomePositionAltitude READ plannedHomePositionAltitude CONSTANT)
Q_PROPERTY(QObject* cameraSection READ cameraSection CONSTANT)

2
src/MissionManager/MissionSettingsTest.cc

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

2
src/MissionManager/PlanMasterController.h

@ -29,7 +29,7 @@ class PlanMasterController : public QObject @@ -29,7 +29,7 @@ class PlanMasterController : public QObject
public:
PlanMasterController(QObject* parent = nullptr);
#ifdef QT_DEBUG
// Used by test code to create master controll with specific firmware/vehicle type
// Used by test code to create master controller with specific firmware/vehicle type
PlanMasterController(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, QObject* parent = nullptr);
#endif

1
src/MissionManager/PlanMasterControllerTest.cc

@ -35,7 +35,6 @@ void PlanMasterControllerTest::cleanup(void) @@ -35,7 +35,6 @@ void PlanMasterControllerTest::cleanup(void)
{
delete _masterController;
_masterController = nullptr;
UnitTest::cleanup();
}

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(_masterController, false /* flyView */, missionItem, this);
_simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, missionItem);
}
void SectionTest::cleanup(void)
@ -62,13 +62,13 @@ void SectionTest::_commonScanTest(Section* section) @@ -62,13 +62,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(_masterController, false /* flyView */, waypointItem, this);
SimpleMissionItem simpleItem(_masterController, false /* flyView */, waypointItem);
waypointVisualItems.append(&simpleItem);
waypointVisualItems.append(&simpleItem);
waypointVisualItems.append(&simpleItem);
QmlObjectListModel complexVisualItems;
SurveyComplexItem surveyItem(_masterController, false /* fly View */, QString() /* kmlFile */, this /* parent */);
SurveyComplexItem surveyItem(_masterController, false /* fly View */, QString() /* kmlFile */);
complexVisualItems.append(&surveyItem);
// This tests the common cases which should not lead to scan succeess

8
src/MissionManager/SimpleMissionItem.cc

@ -52,8 +52,8 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = { @@ -52,8 +52,8 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = {
{ "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT },
};
SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, bool forLoad, QObject* parent)
: VisualMissionItem (masterController, flyView, parent)
SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, bool forLoad)
: VisualMissionItem (masterController, flyView)
, _commandTree (qgcApp()->toolbox()->missionCommandTree())
, _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32)
, _altitudeFact (0, "Altitude", FactMetaData::valueTypeDouble)
@ -80,8 +80,8 @@ SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, boo @@ -80,8 +80,8 @@ SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, boo
}
}
SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, const MissionItem& missionItem, QObject* parent)
: VisualMissionItem (masterController, flyView, parent)
SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, const MissionItem& missionItem)
: VisualMissionItem (masterController, flyView)
, _missionItem (missionItem)
, _commandTree (qgcApp()->toolbox()->missionCommandTree())
, _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32)

4
src/MissionManager/SimpleMissionItem.h

@ -24,8 +24,8 @@ class SimpleMissionItem : public VisualMissionItem @@ -24,8 +24,8 @@ class SimpleMissionItem : public VisualMissionItem
Q_OBJECT
public:
SimpleMissionItem(PlanMasterController* masterController, bool flyView, bool forLoad, QObject* parent);
SimpleMissionItem(PlanMasterController* masterController, bool flyView, const MissionItem& missionItem, QObject* parent);
SimpleMissionItem(PlanMasterController* masterController, bool flyView, bool forLoad);
SimpleMissionItem(PlanMasterController* masterController, bool flyView, const MissionItem& missionItem);
~SimpleMissionItem();

24
src/MissionManager/SimpleMissionItemTest.cc

@ -69,14 +69,7 @@ const ItemExpected_t _rgItemExpected[] = { @@ -69,14 +69,7 @@ const ItemExpected_t _rgItemExpected[] = {
SimpleMissionItemTest::SimpleMissionItemTest(void)
: _simpleItem(nullptr)
{
}
void SimpleMissionItemTest::init(void)
{
VisualMissionItemTest::init();
{
rgSimpleItemSignals[commandChangedIndex] = SIGNAL(commandChanged(int));
rgSimpleItemSignals[altitudeModeChangedIndex] = SIGNAL(altitudeModeChanged());
rgSimpleItemSignals[friendlyEditAllowedChangedIndex] = SIGNAL(friendlyEditAllowedChanged(bool));
@ -84,6 +77,11 @@ void SimpleMissionItemTest::init(void) @@ -84,6 +77,11 @@ void SimpleMissionItemTest::init(void)
rgSimpleItemSignals[rawEditChangedIndex] = SIGNAL(rawEditChanged(bool));
rgSimpleItemSignals[cameraSectionChangedIndex] = SIGNAL(cameraSectionChanged(QObject*));
rgSimpleItemSignals[speedSectionChangedIndex] = SIGNAL(speedSectionChanged(QObject*));
}
void SimpleMissionItemTest::init(void)
{
VisualMissionItemTest::init();
MissionItem missionItem(1, // sequence number
MAV_CMD_NAV_WAYPOINT,
@ -97,7 +95,7 @@ void SimpleMissionItemTest::init(void) @@ -97,7 +95,7 @@ void SimpleMissionItemTest::init(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
_simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, missionItem, this);
_simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, missionItem);
// 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
@ -110,8 +108,10 @@ void SimpleMissionItemTest::init(void) @@ -110,8 +108,10 @@ void SimpleMissionItemTest::init(void)
void SimpleMissionItemTest::cleanup(void)
{
delete _simpleItem;
VisualMissionItemTest::cleanup();
// These items go away from _masterController is deleted
_simpleItem = nullptr;
}
bool SimpleMissionItemTest::_classMatch(QGCMAVLink::VehicleClass_t vehicleClass, QGCMAVLink::VehicleClass_t testClass)
@ -162,7 +162,7 @@ void SimpleMissionItemTest::_testEditorFactsWorker(QGCMAVLink::VehicleClass_t ve @@ -162,7 +162,7 @@ void SimpleMissionItemTest::_testEditorFactsWorker(QGCMAVLink::VehicleClass_t ve
70.1234567,
true, // autoContinue
false); // isCurrentItem
SimpleMissionItem simpleMissionItem(&planController, false /* flyView */, missionItem, nullptr);
SimpleMissionItem simpleMissionItem(&planController, false /* flyView */, missionItem);
MissionController::MissionFlightStatus_t missionFlightStatus;
missionFlightStatus.vtolMode = vtolMode;
@ -240,7 +240,7 @@ void SimpleMissionItemTest::_testEditorFacts(void) @@ -240,7 +240,7 @@ void SimpleMissionItemTest::_testEditorFacts(void)
void SimpleMissionItemTest::_testDefaultValues(void)
{
SimpleMissionItem item(_masterController, false /* flyView */, false /* forLoad */, nullptr);
SimpleMissionItem item(_masterController, false /* flyView */, false /* forLoad */);
item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);

6
src/MissionManager/SpeedSectionTest.cc

@ -135,7 +135,7 @@ void SpeedSectionTest::_checkAvailable(void) @@ -135,7 +135,7 @@ void SpeedSectionTest::_checkAvailable(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
SimpleMissionItem* item = new SimpleMissionItem(_masterController, false /* flyView */, missionItem, this);
SimpleMissionItem* item = new SimpleMissionItem(_masterController, false /* flyView */, missionItem);
QVERIFY(item->speedSection());
QCOMPARE(item->speedSection()->available(), false);
}
@ -194,7 +194,7 @@ void SpeedSectionTest::_testScanForSection(void) @@ -194,7 +194,7 @@ void SpeedSectionTest::_testScanForSection(void)
double flightSpeed = 10.123456;
MissionItem validSpeedItem(0, MAV_CMD_DO_CHANGE_SPEED, MAV_FRAME_MISSION, _controllerVehicle->multiRotor() ? 1 : 0, flightSpeed, -1, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleItem(_masterController, false /* flyView */, validSpeedItem, nullptr);
SimpleMissionItem simpleItem(_masterController, false /* flyView */, validSpeedItem);
MissionItem& simpleMissionItem = simpleItem.missionItem();
visualItems.append(&simpleItem);
scanIndex = 0;
@ -265,7 +265,7 @@ void SpeedSectionTest::_testScanForSection(void) @@ -265,7 +265,7 @@ void SpeedSectionTest::_testScanForSection(void)
// Valid item in wrong position
MissionItem waypointMissionItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleWaypointItem(_masterController, false /* flyView */, waypointMissionItem, nullptr);
SimpleMissionItem simpleWaypointItem(_masterController, false /* flyView */, waypointMissionItem);
simpleMissionItem = validSpeedItem;
visualItems.append(&simpleWaypointItem);
visualItems.append(&simpleMissionItem);

4
src/MissionManager/StructureScanComplexItem.cc

@ -36,8 +36,8 @@ const char* StructureScanComplexItem::startFromTopName = "StartFromTo @@ -36,8 +36,8 @@ const char* StructureScanComplexItem::startFromTopName = "StartFromTo
const char* StructureScanComplexItem::jsonComplexItemTypeValue = "StructureScan";
const char* StructureScanComplexItem::_jsonCameraCalcKey = "CameraCalc";
StructureScanComplexItem::StructureScanComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrShpFile, QObject* parent)
: ComplexMissionItem (masterController, flyView, parent)
StructureScanComplexItem::StructureScanComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrShpFile)
: ComplexMissionItem (masterController, flyView)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/StructureScan.SettingsGroup.json"), this /* QObject parent */))
, _sequenceNumber (0)
, _entryVertex (0)

2
src/MissionManager/StructureScanComplexItem.h

@ -29,7 +29,7 @@ class StructureScanComplexItem : public ComplexMissionItem @@ -29,7 +29,7 @@ class StructureScanComplexItem : public ComplexMissionItem
public:
/// @param flyView true: Created for use in the Fly View, false: Created for use in the Plan View
/// @param kmlOrSHPFile Polygon comes from this file, empty for default polygon
StructureScanComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrSHPFile, QObject* parent);
StructureScanComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrSHPFile);
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
Q_PROPERTY(Fact* entranceAlt READ entranceAlt CONSTANT)

14
src/MissionManager/StructureScanComplexItemTest.cc

@ -24,8 +24,7 @@ void StructureScanComplexItemTest::init(void) @@ -24,8 +24,7 @@ void StructureScanComplexItemTest::init(void)
_rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_masterController = new PlanMasterController(this);
_controllerVehicle = _masterController->controllerVehicle();
_structureScanItem = new StructureScanComplexItem(new PlanMasterController(this), false /* flyView */, QString() /* kmlFile */, this /* parent */);
_structureScanItem = new StructureScanComplexItem(_masterController, false /* flyView */, QString() /* kmlFile */);
_structureScanItem->setDirty(false);
_multiSpy = new MultiSignalSpy();
@ -35,7 +34,14 @@ void StructureScanComplexItemTest::init(void) @@ -35,7 +34,14 @@ void StructureScanComplexItemTest::init(void)
void StructureScanComplexItemTest::cleanup(void)
{
delete _structureScanItem;
delete _masterController;
delete _multiSpy;
_masterController = nullptr;
_structureScanItem = nullptr; // Deleted when _masterController is deleted
_multiSpy = nullptr;
UnitTest::cleanup();
}
void StructureScanComplexItemTest::_testDirty(void)
@ -114,7 +120,7 @@ void StructureScanComplexItemTest::_testSaveLoad(void) @@ -114,7 +120,7 @@ void StructureScanComplexItemTest::_testSaveLoad(void)
_structureScanItem->save(items);
QString errorString;
StructureScanComplexItem* newItem = new StructureScanComplexItem(new PlanMasterController(this), false /* flyView */, QString() /* kmlFile */, this /* parent */);
StructureScanComplexItem* newItem = new StructureScanComplexItem(_masterController, false /* flyView */, QString() /* kmlFile */);
QVERIFY(newItem->load(items[0].toObject(), 10, errorString));
QVERIFY(errorString.isEmpty());
_validateItem(newItem);

1
src/MissionManager/StructureScanComplexItemTest.h

@ -47,7 +47,6 @@ private: @@ -47,7 +47,6 @@ private:
const char* _rgSignals[_cSignals];
PlanMasterController* _masterController = nullptr;
Vehicle* _controllerVehicle = nullptr;
MultiSignalSpy* _multiSpy = nullptr;
StructureScanComplexItem* _structureScanItem = nullptr;
QList<QGeoCoordinate> _polyPoints;

4
src/MissionManager/SurveyComplexItem.cc

@ -64,8 +64,8 @@ const char* SurveyComplexItem::_jsonV3Refly90DegreesKey = "refly90 @@ -64,8 +64,8 @@ const char* SurveyComplexItem::_jsonV3Refly90DegreesKey = "refly90
const char* SurveyComplexItem::_jsonFlyAlternateTransectsKey = "flyAlternateTransects";
const char* SurveyComplexItem::_jsonSplitConcavePolygonsKey = "splitConcavePolygons";
SurveyComplexItem::SurveyComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrShpFile, QObject* parent)
: TransectStyleComplexItem (masterController, flyView, settingsGroup, parent)
SurveyComplexItem::SurveyComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrShpFile)
: TransectStyleComplexItem (masterController, flyView, settingsGroup)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this))
, _gridAngleFact (settingsGroup, _metaDataMap[gridAngleName])
, _flyAlternateTransectsFact(settingsGroup, _metaDataMap[flyAlternateTransectsName])

2
src/MissionManager/SurveyComplexItem.h

@ -25,7 +25,7 @@ class SurveyComplexItem : public TransectStyleComplexItem @@ -25,7 +25,7 @@ class SurveyComplexItem : public TransectStyleComplexItem
public:
/// @param flyView true: Created for use in the Fly View, false: Created for use in the Plan View
/// @param kmlOrShpFile Polygon comes from this file, empty for default polygon
SurveyComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrShpFile, QObject* parent);
SurveyComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrShpFile);
Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT)
Q_PROPERTY(Fact* flyAlternateTransects READ flyAlternateTransects CONSTANT)

21
src/MissionManager/SurveyComplexItemTest.cc

@ -13,6 +13,13 @@ @@ -13,6 +13,13 @@
SurveyComplexItemTest::SurveyComplexItemTest(void)
{
_rgSurveySignals[surveyVisualTransectPointsChangedIndex] = SIGNAL(visualTransectPointsChanged());
_rgSurveySignals[surveyCameraShotsChangedIndex] = SIGNAL(cameraShotsChanged());
_rgSurveySignals[surveyCoveredAreaChangedIndex] = SIGNAL(coveredAreaChanged());
_rgSurveySignals[surveyTimeBetweenShotsChangedIndex] = SIGNAL(timeBetweenShotsChanged());
_rgSurveySignals[surveyRefly90DegreesChangedIndex] = SIGNAL(refly90DegreesChanged(bool));
_rgSurveySignals[surveyDirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
// We use a 100m by 100m square test polygon
const double edgeDistance = 100;
_polyVertices.append(QGeoCoordinate(47.633550640000003, -122.08982199));
@ -25,14 +32,7 @@ void SurveyComplexItemTest::init(void) @@ -25,14 +32,7 @@ void SurveyComplexItemTest::init(void)
{
TransectStyleComplexItemTestBase::init();
_rgSurveySignals[surveyVisualTransectPointsChangedIndex] = SIGNAL(visualTransectPointsChanged());
_rgSurveySignals[surveyCameraShotsChangedIndex] = SIGNAL(cameraShotsChanged());
_rgSurveySignals[surveyCoveredAreaChangedIndex] = SIGNAL(coveredAreaChanged());
_rgSurveySignals[surveyTimeBetweenShotsChangedIndex] = SIGNAL(timeBetweenShotsChanged());
_rgSurveySignals[surveyRefly90DegreesChangedIndex] = SIGNAL(refly90DegreesChanged(bool));
_rgSurveySignals[surveyDirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_surveyItem = new SurveyComplexItem(_masterController, false /* flyView */, QString() /* kmlFile */, this /* parent */);
_surveyItem = new SurveyComplexItem(_masterController, false /* flyView */, QString() /* kmlFile */);
_mapPolygon = _surveyItem->surveyAreaPolygon();
_mapPolygon->appendVertices(_polyVertices);
@ -61,10 +61,13 @@ void SurveyComplexItemTest::init(void) @@ -61,10 +61,13 @@ void SurveyComplexItemTest::init(void)
void SurveyComplexItemTest::cleanup(void)
{
delete _surveyItem;
delete _multiSpy;
_multiSpy = nullptr;
TransectStyleComplexItemTestBase::cleanup();
// These items are deleted when _masterController is deleted
_surveyItem = nullptr;
}
void SurveyComplexItemTest::_testDirty(void)

12
src/MissionManager/TakeoffMissionItem.cc

@ -20,23 +20,23 @@ @@ -20,23 +20,23 @@
#include "SettingsManager.h"
#include "PlanMasterController.h"
TakeoffMissionItem::TakeoffMissionItem(PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, bool forLoad, QObject* parent)
: SimpleMissionItem (masterController, flyView, forLoad, parent)
TakeoffMissionItem::TakeoffMissionItem(PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, bool forLoad)
: SimpleMissionItem (masterController, flyView, forLoad)
, _settingsItem (settingsItem)
{
_init(forLoad);
}
TakeoffMissionItem::TakeoffMissionItem(MAV_CMD takeoffCmd, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
: SimpleMissionItem (masterController, flyView, false /* forLoad */, parent)
TakeoffMissionItem::TakeoffMissionItem(MAV_CMD takeoffCmd, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem)
: SimpleMissionItem (masterController, flyView, false /* forLoad */)
, _settingsItem (settingsItem)
{
setCommand(takeoffCmd);
_init(false /* forLoad */);
}
TakeoffMissionItem::TakeoffMissionItem(const MissionItem& missionItem, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
: SimpleMissionItem (masterController, flyView, missionItem, parent)
TakeoffMissionItem::TakeoffMissionItem(const MissionItem& missionItem, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem)
: SimpleMissionItem (masterController, flyView, missionItem)
, _settingsItem (settingsItem)
{
_init(false /* forLoad */);

6
src/MissionManager/TakeoffMissionItem.h

@ -21,9 +21,9 @@ class TakeoffMissionItem : public SimpleMissionItem @@ -21,9 +21,9 @@ class TakeoffMissionItem : public SimpleMissionItem
Q_OBJECT
public:
TakeoffMissionItem(PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, bool forLoad, QObject* parent);
TakeoffMissionItem(MAV_CMD takeoffCmd, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
TakeoffMissionItem(const MissionItem& missionItem, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
TakeoffMissionItem(PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, bool forLoad);
TakeoffMissionItem(MAV_CMD takeoffCmd, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem);
TakeoffMissionItem(const MissionItem& missionItem, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem);
Q_PROPERTY(QGeoCoordinate launchCoordinate READ launchCoordinate WRITE setLaunchCoordinate NOTIFY launchCoordinateChanged)
Q_PROPERTY(bool launchTakeoffAtSameLocation READ launchTakeoffAtSameLocation WRITE setLaunchTakeoffAtSameLocation NOTIFY launchTakeoffAtSameLocationChanged)

4
src/MissionManager/TransectStyleComplexItem.cc

@ -43,8 +43,8 @@ const char* TransectStyleComplexItem::_jsonCameraShotsKey = "C @@ -43,8 +43,8 @@ const char* TransectStyleComplexItem::_jsonCameraShotsKey = "C
const char* TransectStyleComplexItem::_jsonTerrainFollowKeyDeprecated = "FollowTerrain";
TransectStyleComplexItem::TransectStyleComplexItem(PlanMasterController* masterController, bool flyView, QString settingsGroup, QObject* parent)
: ComplexMissionItem (masterController, flyView, parent)
TransectStyleComplexItem::TransectStyleComplexItem(PlanMasterController* masterController, bool flyView, QString settingsGroup)
: ComplexMissionItem (masterController, flyView)
, _cameraCalc (masterController, settingsGroup)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/TransectStyle.SettingsGroup.json"), this))
, _turnAroundDistanceFact (settingsGroup, _metaDataMap[_controllerVehicle->multiRotor() ? turnAroundDistanceMultiRotorName : turnAroundDistanceName])

2
src/MissionManager/TransectStyleComplexItem.h

@ -27,7 +27,7 @@ class TransectStyleComplexItem : public ComplexMissionItem @@ -27,7 +27,7 @@ class TransectStyleComplexItem : public ComplexMissionItem
Q_OBJECT
public:
TransectStyleComplexItem(PlanMasterController* masterController, bool flyView, QString settignsGroup, QObject* parent);
TransectStyleComplexItem(PlanMasterController* masterController, bool flyView, QString settignsGroup);
Q_PROPERTY(QGCMapPolygon* surveyAreaPolygon READ surveyAreaPolygon CONSTANT)
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)

12
src/MissionManager/TransectStyleComplexItemTest.cc

@ -19,7 +19,7 @@ void TransectStyleComplexItemTest::init(void) @@ -19,7 +19,7 @@ void TransectStyleComplexItemTest::init(void)
{
TransectStyleComplexItemTestBase::init();
_transectStyleItem = new TestTransectStyleItem(_masterController, this);
_transectStyleItem = new TestTransectStyleItem(_masterController);
_transectStyleItem->cameraTriggerInTurnAround()->setRawValue(false);
_transectStyleItem->cameraCalc()->setCameraBrand(CameraCalc::canonicalManualCameraName());
_transectStyleItem->cameraCalc()->valueSetIsDistance()->setRawValue(true);
@ -32,9 +32,13 @@ void TransectStyleComplexItemTest::init(void) @@ -32,9 +32,13 @@ void TransectStyleComplexItemTest::init(void)
void TransectStyleComplexItemTest::cleanup(void)
{
delete _transectStyleItem;
delete _multiSpy;
_multiSpy = nullptr;
TransectStyleComplexItemTestBase::cleanup();
// These items are deleted when _masterController is deleted
_transectStyleItem = nullptr;
}
void TransectStyleComplexItemTest::_testDirty(void)
@ -223,8 +227,8 @@ void TransectStyleComplexItemTest::_testFollowTerrain(void) @@ -223,8 +227,8 @@ void TransectStyleComplexItemTest::_testFollowTerrain(void)
}
}
TestTransectStyleItem::TestTransectStyleItem(PlanMasterController* masterController, QObject* parent)
: TransectStyleComplexItem (masterController, false /* flyView */, QStringLiteral("UnitTestTransect"), parent)
TestTransectStyleItem::TestTransectStyleItem(PlanMasterController* masterController)
: TransectStyleComplexItem (masterController, false /* flyView */, QStringLiteral("UnitTestTransect"))
, rebuildTransectsPhase1Called (false)
, recalcComplexDistanceCalled (false)
, recalcCameraShotsCalled (false)

2
src/MissionManager/TransectStyleComplexItemTest.h

@ -46,7 +46,7 @@ class TestTransectStyleItem : public TransectStyleComplexItem @@ -46,7 +46,7 @@ class TestTransectStyleItem : public TransectStyleComplexItem
Q_OBJECT
public:
TestTransectStyleItem(PlanMasterController* masterController, QObject* parent = nullptr);
TestTransectStyleItem(PlanMasterController* masterController);
void adjustSurveAreaPolygon(void);

8
src/MissionManager/TransectStyleComplexItemTestBase.cc

@ -26,9 +26,11 @@ void TransectStyleComplexItemTestBase::init(void) @@ -26,9 +26,11 @@ void TransectStyleComplexItemTestBase::init(void)
void TransectStyleComplexItemTestBase::cleanup(void)
{
delete _masterController;
_planViewSettings = nullptr;
_masterController = nullptr;
_controllerVehicle = nullptr;
_planViewSettings = nullptr;
_masterController = nullptr;
_controllerVehicle = nullptr;
UnitTest::cleanup();
}

4
src/MissionManager/VTOLLandingComplexItem.cc

@ -25,8 +25,8 @@ const QString VTOLLandingComplexItem::name(tr("VTOL Landing")); @@ -25,8 +25,8 @@ const QString VTOLLandingComplexItem::name(tr("VTOL Landing"));
const char* VTOLLandingComplexItem::settingsGroup = "VTOLLanding";
const char* VTOLLandingComplexItem::jsonComplexItemTypeValue = "vtolLandingPattern";
VTOLLandingComplexItem::VTOLLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: LandingComplexItem (masterController, flyView, parent)
VTOLLandingComplexItem::VTOLLandingComplexItem(PlanMasterController* masterController, bool flyView)
: LandingComplexItem (masterController, flyView)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/VTOLLandingPattern.FactMetaData.json"), this))
, _landingDistanceFact (settingsGroup, _metaDataMap[finalApproachToLandDistanceName])
, _finalApproachAltitudeFact(settingsGroup, _metaDataMap[finalApproachAltitudeName])

4
src/MissionManager/VTOLLandingComplexItem.h

@ -24,7 +24,7 @@ class VTOLLandingComplexItem : public LandingComplexItem @@ -24,7 +24,7 @@ class VTOLLandingComplexItem : public LandingComplexItem
Q_OBJECT
public:
VTOLLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent);
VTOLLandingComplexItem(PlanMasterController* masterController, bool flyView);
/// Scans the loaded items for a landing pattern complex item
static bool scanForItem(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController);
@ -47,7 +47,7 @@ private slots: @@ -47,7 +47,7 @@ private slots:
void _updateFlightPathSegmentsDontCallDirectly(void) override;
private:
static LandingComplexItem* _createItem (PlanMasterController* masterController, bool flyView, QObject* parent) { return new VTOLLandingComplexItem(masterController, flyView, parent); }
static LandingComplexItem* _createItem (PlanMasterController* masterController, bool flyView) { return new VTOLLandingComplexItem(masterController, flyView); }
static bool _isValidLandItem(const MissionItem& missionItem);
// Overrides from LandingComplexItem

12
src/MissionManager/VisualMissionItem.cc

@ -23,8 +23,10 @@ const char* VisualMissionItem::jsonTypeKey = "type"; @@ -23,8 +23,10 @@ const char* VisualMissionItem::jsonTypeKey = "type";
const char* VisualMissionItem::jsonTypeSimpleItemValue = "SimpleItem";
const char* VisualMissionItem::jsonTypeComplexItemValue = "ComplexItem";
VisualMissionItem::VisualMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: QObject (parent)
// All VisualMissionItem derived classes are parented to masterController in order to tie their lifecycles together.
VisualMissionItem::VisualMissionItem(PlanMasterController* masterController, bool flyView)
: QObject (masterController)
, _flyView (flyView)
, _masterController (masterController)
, _missionController(masterController->missionController())
@ -33,8 +35,8 @@ VisualMissionItem::VisualMissionItem(PlanMasterController* masterController, boo @@ -33,8 +35,8 @@ VisualMissionItem::VisualMissionItem(PlanMasterController* masterController, boo
_commonInit();
}
VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, bool flyView, QObject* parent)
: QObject (parent)
VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, bool flyView)
: QObject (other._masterController)
, _flyView (flyView)
{
*this = other;
@ -57,6 +59,8 @@ void VisualMissionItem::_commonInit(void) @@ -57,6 +59,8 @@ void VisualMissionItem::_commonInit(void)
const VisualMissionItem& VisualMissionItem::operator=(const VisualMissionItem& other)
{
setParent(other._masterController);
_masterController = other._masterController;
_controllerVehicle = other._controllerVehicle;

4
src/MissionManager/VisualMissionItem.h

@ -36,8 +36,8 @@ class VisualMissionItem : public QObject @@ -36,8 +36,8 @@ class VisualMissionItem : public QObject
Q_OBJECT
public:
VisualMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent);
VisualMissionItem(const VisualMissionItem& other, bool flyView, QObject* parent);
VisualMissionItem(PlanMasterController* masterController, bool flyView);
VisualMissionItem(const VisualMissionItem& other, bool flyView);
~VisualMissionItem();

6
src/MissionManager/VisualMissionItemTest.cc

@ -51,8 +51,12 @@ void VisualMissionItemTest::init(void) @@ -51,8 +51,12 @@ void VisualMissionItemTest::init(void)
void VisualMissionItemTest::cleanup(void)
{
delete _masterController;
_masterController = nullptr;
_controllerVehicle = nullptr;
UnitTest::cleanup();
_masterController->deleteLater();
}
void VisualMissionItemTest::_createSpy(VisualMissionItem* visualItem, MultiSignalSpy** visualSpy)

Loading…
Cancel
Save