diff --git a/src/MissionManager/CameraCalc.h b/src/MissionManager/CameraCalc.h index 95eeb1195c0de0d9703c9ce6816bc8c001fead7b..01b96b89f19a40e905f661f80fba0e48a5de0dc0 100644 --- a/src/MissionManager/CameraCalc.h +++ b/src/MissionManager/CameraCalc.h @@ -19,7 +19,7 @@ class CameraCalc : public CameraSpec Q_OBJECT public: - CameraCalc(Vehicle* vehicle, const QString& settingsGroup, QObject* parent = NULL); + CameraCalc(Vehicle* vehicle, const QString& settingsGroup, QObject* parent = nullptr); Q_PROPERTY(QString customCameraName READ customCameraName CONSTANT) ///< Camera name for custom camera setting Q_PROPERTY(QString manualCameraName READ manualCameraName CONSTANT) ///< Camera name for manual camera setting diff --git a/src/MissionManager/CameraCalcTest.cc b/src/MissionManager/CameraCalcTest.cc index 10571ce12462488110065a867ebcb0ffcea489b2..c0628acad853951f31dc885d7ea40ef364312cb1 100644 --- a/src/MissionManager/CameraCalcTest.cc +++ b/src/MissionManager/CameraCalcTest.cc @@ -11,7 +11,7 @@ #include "QGCApplication.h" CameraCalcTest::CameraCalcTest(void) - : _offlineVehicle(NULL) + : _offlineVehicle(nullptr) { } diff --git a/src/MissionManager/CameraSection.cc b/src/MissionManager/CameraSection.cc index 89ddc77fe9e0d9abb4056ee8258c14c9fd2dc618..e605a7b215f0e29286aa7574ef54d22a4fa1d249 100644 --- a/src/MissionManager/CameraSection.cc +++ b/src/MissionManager/CameraSection.cc @@ -147,7 +147,7 @@ void CameraSection::appendSectionItems(QList& items, QObject* miss } if (_cameraActionFact.rawValue().toInt() != CameraActionNone) { - MissionItem* item = NULL; + MissionItem* item = nullptr; switch (_cameraActionFact.rawValue().toInt()) { case TakePhotosIntervalTime: diff --git a/src/MissionManager/CameraSection.h b/src/MissionManager/CameraSection.h index 49f230896261307710a14a00fffdaaa25aedec4a..be84dcc990f06f73ac88d38f289cd214b510f9cc 100644 --- a/src/MissionManager/CameraSection.h +++ b/src/MissionManager/CameraSection.h @@ -21,7 +21,7 @@ class CameraSection : public Section Q_OBJECT public: - CameraSection(Vehicle* vehicle, QObject* parent = NULL); + CameraSection(Vehicle* vehicle, QObject* parent = nullptr); // These enum values must match the json meta data diff --git a/src/MissionManager/CameraSectionTest.cc b/src/MissionManager/CameraSectionTest.cc index 18eef23d29d2be8aac2a42fde82ad0aede88277c..476f1a13758fefa00baa5cc2a87f37944bbec02c 100644 --- a/src/MissionManager/CameraSectionTest.cc +++ b/src/MissionManager/CameraSectionTest.cc @@ -13,16 +13,16 @@ #include "MissionCommandUIInfo.h" CameraSectionTest::CameraSectionTest(void) - : _spyCamera (NULL) - , _spySection (NULL) - , _cameraSection (NULL) - , _validGimbalItem (NULL) - , _validDistanceItem (NULL) - , _validTimeItem (NULL) - , _validStartVideoItem (NULL) - , _validCameraPhotoModeItem (NULL) - , _validCameraVideoModeItem (NULL) - , _validCameraSurveyPhotoModeItem (NULL) + : _spyCamera (nullptr) + , _spySection (nullptr) + , _cameraSection (nullptr) + , _validGimbalItem (nullptr) + , _validDistanceItem (nullptr) + , _validTimeItem (nullptr) + , _validStartVideoItem (nullptr) + , _validCameraPhotoModeItem (nullptr) + , _validCameraVideoModeItem (nullptr) + , _validCameraSurveyPhotoModeItem (nullptr) { } @@ -143,7 +143,7 @@ void CameraSectionTest::cleanup(void) void CameraSectionTest::_createSpy(CameraSection* cameraSection, MultiSignalSpy** cameraSpy) { - *cameraSpy = NULL; + *cameraSpy = nullptr; MultiSignalSpy* spy = new MultiSignalSpy(); QCOMPARE(spy->init(cameraSection, rgCameraSignals, cCameraSignals), true); *cameraSpy = spy; @@ -618,7 +618,7 @@ void CameraSectionTest::_testScanForGimbalSection(void) // Gimbal command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validGimbalItem->missionItem(), NULL); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validGimbalItem->missionItem(), nullptr); invalidSimpleItem.missionItem().setParam2(10); // roll is not supported visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -708,7 +708,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void) */ // Mode command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validCameraPhotoModeItem->missionItem(), NULL); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validCameraPhotoModeItem->missionItem(), nullptr); invalidSimpleItem.missionItem().setParam3(1); // Param3 should be NaN visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -747,7 +747,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void) // Image start command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validTimeItem->missionItem(), NULL); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validTimeItem->missionItem(), nullptr); invalidSimpleItem.missionItem().setParam3(10); // must be 0 for unlimited visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -788,7 +788,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) // Trigger distance command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validDistanceItem->missionItem(), NULL); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validDistanceItem->missionItem(), nullptr); invalidSimpleItem.missionItem().setParam1(-1); // must be >= 0 visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -873,7 +873,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) // Start Video command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validStartVideoItem->missionItem(), NULL); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validStartVideoItem->missionItem(), nullptr); invalidSimpleItem.missionItem().setParam1(10); // Reserved (must be 0) visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -909,7 +909,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void) // Trigger distance command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validStopVideoItem->missionItem(), NULL); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validStopVideoItem->missionItem(), nullptr); invalidSimpleItem.missionItem().setParam1(10); // must be 0 visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); @@ -949,8 +949,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void) // Out of order commands - SimpleMissionItem validStopDistanceItem(_offlineVehicle, false /* flyView */, NULL); - SimpleMissionItem validStopTimeItem(_offlineVehicle, false /* flyView */, NULL); + SimpleMissionItem validStopDistanceItem(_offlineVehicle, false /* flyView */, nullptr); + SimpleMissionItem validStopTimeItem(_offlineVehicle, false /* flyView */, nullptr); validStopDistanceItem.missionItem() = _validStopDistanceItem->missionItem(); validStopTimeItem.missionItem() = _validStopTimeItem->missionItem(); visualItems.append(&validStopTimeItem); @@ -990,7 +990,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void) // Take Photo command but incorrect settings - SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validTimeItem->missionItem(), NULL); + SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validTimeItem->missionItem(), nullptr); invalidSimpleItem.missionItem().setParam3(10); // must be 1 for single photo visualItems.append(&invalidSimpleItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); diff --git a/src/MissionManager/CameraSpec.h b/src/MissionManager/CameraSpec.h index bf32047d0dfe46a1b19f99fc7b4a71196043a757..261c8827811e6f384d9d6544f7fc8cb6548f2484 100644 --- a/src/MissionManager/CameraSpec.h +++ b/src/MissionManager/CameraSpec.h @@ -16,7 +16,7 @@ class CameraSpec : public QObject Q_OBJECT public: - CameraSpec(const QString& settingsGroup, QObject* parent = NULL); + CameraSpec(const QString& settingsGroup, QObject* parent = nullptr); const CameraSpec& operator=(const CameraSpec& other); diff --git a/src/MissionManager/CorridorScanComplexItem.cc b/src/MissionManager/CorridorScanComplexItem.cc index f253f8d8e74efc46c3bc127edb25e3435e39202c..0ae723c17c9b1ea67cae624236d6f0a6d8092f7e 100644 --- a/src/MissionManager/CorridorScanComplexItem.cc +++ b/src/MissionManager/CorridorScanComplexItem.cc @@ -335,7 +335,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) if (_loadedMissionItemsParent) { _loadedMissionItems.clear(); _loadedMissionItemsParent->deleteLater(); - _loadedMissionItemsParent = NULL; + _loadedMissionItemsParent = nullptr; } _transects.clear(); diff --git a/src/MissionManager/CorridorScanComplexItemTest.cc b/src/MissionManager/CorridorScanComplexItemTest.cc index 3086fb97972f1548b7356670a7cb7ce9c2db7afe..75f330ac4e9f53f72caccc4364cafaa441a51bce 100644 --- a/src/MissionManager/CorridorScanComplexItemTest.cc +++ b/src/MissionManager/CorridorScanComplexItemTest.cc @@ -11,7 +11,7 @@ #include "QGCApplication.h" CorridorScanComplexItemTest::CorridorScanComplexItemTest(void) - : _offlineVehicle(NULL) + : _offlineVehicle(nullptr) { _linePoints << QGeoCoordinate(47.633550640000003, -122.08982199) << QGeoCoordinate(47.634129020000003, -122.08887249) diff --git a/src/MissionManager/MissionCommandList.h b/src/MissionManager/MissionCommandList.h index 319020002311e3b50400e6eb2679326ff1cb6c96..862d5dd6a9c23653abb7bb09d35059b6c11782b8 100644 --- a/src/MissionManager/MissionCommandList.h +++ b/src/MissionManager/MissionCommandList.h @@ -30,7 +30,7 @@ class MissionCommandList : public QObject public: /// @param jsonFilename Json file which contains commands /// @param baseCommandList true: bottomost level of mission command hierarchy (partial not allowed), false: mid-level of command hierarchy - MissionCommandList(const QString& jsonFilename, bool baseCommandList, QObject* parent = NULL); + MissionCommandList(const QString& jsonFilename, bool baseCommandList, QObject* parent = nullptr); /// Returns list of categories in this list QStringList& categories(void) { return _categories; } diff --git a/src/MissionManager/MissionCommandTreeTest.cc b/src/MissionManager/MissionCommandTreeTest.cc index 4a414fc874e938acfed5574d70dab3e5b6b68542..89a86f559525a4f90ca6ec6dfc41a20e01c4262e 100644 --- a/src/MissionManager/MissionCommandTreeTest.cc +++ b/src/MissionManager/MissionCommandTreeTest.cc @@ -59,7 +59,7 @@ void MissionCommandTreeTest::_checkFullInfoMap(const MissionCommandUIInfo* uiInf // Verifies that values match settings for base tree void MissionCommandTreeTest::_checkBaseValues(const MissionCommandUIInfo* uiInfo, int command) { - QVERIFY(uiInfo != NULL); + QVERIFY(uiInfo != nullptr); _checkFullInfoMap(uiInfo); QCOMPARE(uiInfo->command(), (MAV_CMD)command); QCOMPARE(uiInfo->rawName(), _rawName(command)); @@ -116,7 +116,7 @@ void MissionCommandTreeTest::_checkOverrideValues(const MissionCommandUIInfo* ui bool showUI; QString overrideString = QString("override fw %1").arg(command); - QVERIFY(uiInfo != NULL); + QVERIFY(uiInfo != nullptr); _checkFullInfoMap(uiInfo); QCOMPARE(uiInfo->command(), (MAV_CMD)command); QCOMPARE(uiInfo->rawName(), _rawName(command)); @@ -143,11 +143,11 @@ void MissionCommandTreeTest::testJsonLoad(void) // Test loading from the bad command list MissionCommandList* commandList = _commandTree->_staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_GENERIC]; - QVERIFY(commandList != NULL); + QVERIFY(commandList != nullptr); // Command 1 should have all values defaulted, no params MissionCommandUIInfo* uiInfo = commandList->getUIInfo((MAV_CMD)1); - QVERIFY(uiInfo != NULL); + QVERIFY(uiInfo != nullptr); _checkFullInfoMap(uiInfo); QCOMPARE(uiInfo->command(), (MAV_CMD)1); QCOMPARE(uiInfo->rawName(), _rawName(1)); @@ -158,13 +158,13 @@ void MissionCommandTreeTest::testJsonLoad(void) QCOMPARE(uiInfo->isStandaloneCoordinate(), false); QCOMPARE(uiInfo->specifiesCoordinate(), false); for (int i=1; i<=7; i++) { - QVERIFY(uiInfo->getParamInfo(i, showUI) == NULL); + QVERIFY(uiInfo->getParamInfo(i, showUI) == nullptr); QCOMPARE(showUI, false); } // Command 2 should all values defaulted for param 1 uiInfo = commandList->getUIInfo((MAV_CMD)2); - QVERIFY(uiInfo != NULL); + QVERIFY(uiInfo != nullptr); const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(1, showUI); QVERIFY(paramInfo); QCOMPARE(showUI, true); @@ -176,7 +176,7 @@ void MissionCommandTreeTest::testJsonLoad(void) QCOMPARE(paramInfo->param(), 1); QVERIFY(paramInfo->units().isEmpty()); for (int i=2; i<=7; i++) { - QVERIFY(uiInfo->getParamInfo(i, showUI) == NULL); + QVERIFY(uiInfo->getParamInfo(i, showUI) == nullptr); QCOMPARE(showUI, false); } @@ -214,7 +214,7 @@ void MissionCommandTreeTest::testAllTrees(void) } qDebug() << firmwareType << vehicleType; Vehicle* vehicle = new Vehicle(firmwareType, vehicleType, qgcApp()->toolbox()->firmwarePluginManager()); - QVERIFY(qgcApp()->toolbox()->missionCommandTree()->getUIInfo(vehicle, MAV_CMD_NAV_WAYPOINT) != NULL); + QVERIFY(qgcApp()->toolbox()->missionCommandTree()->getUIInfo(vehicle, MAV_CMD_NAV_WAYPOINT) != nullptr); delete vehicle; } } diff --git a/src/MissionManager/MissionCommandUIInfo.h b/src/MissionManager/MissionCommandUIInfo.h index f3c50a714bb57eb51f7c8393be53116d37094c24..8eca1dfd22f00be3fc9884c0c46494bffee7f40d 100644 --- a/src/MissionManager/MissionCommandUIInfo.h +++ b/src/MissionManager/MissionCommandUIInfo.h @@ -42,9 +42,9 @@ class MissionCmdParamInfo : public QObject { Q_OBJECT public: - MissionCmdParamInfo(QObject* parent = NULL); + MissionCmdParamInfo(QObject* parent = nullptr); - MissionCmdParamInfo(const MissionCmdParamInfo& other, QObject* parent = NULL); + MissionCmdParamInfo(const MissionCmdParamInfo& other, QObject* parent = nullptr); const MissionCmdParamInfo& operator=(const MissionCmdParamInfo& other); Q_PROPERTY(int decimalPlaces READ decimalPlaces CONSTANT) @@ -105,9 +105,9 @@ class MissionCommandUIInfo : public QObject { Q_OBJECT public: - MissionCommandUIInfo(QObject* parent = NULL); + MissionCommandUIInfo(QObject* parent = nullptr); - MissionCommandUIInfo(const MissionCommandUIInfo& other, QObject* parent = NULL); + MissionCommandUIInfo(const MissionCommandUIInfo& other, QObject* parent = nullptr); const MissionCommandUIInfo& operator=(const MissionCommandUIInfo& other); Q_PROPERTY(QString category READ category CONSTANT) diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index bd086f31db7e6307cfaad701bf2d27f64262586d..5c5f065e78cb7904f23946aa4ba854f22fafcb72 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -1663,7 +1663,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem) void MissionController::_deinitVisualItem(VisualMissionItem* visualItem) { // Disconnect all signals - disconnect(visualItem, 0, 0, 0); + disconnect(visualItem, nullptr, nullptr, nullptr); } void MissionController::_itemCommandChanged(void) @@ -1677,8 +1677,8 @@ void MissionController::managerVehicleChanged(Vehicle* managerVehicle) if (_managerVehicle) { _missionManager->disconnect(this); _managerVehicle->disconnect(this); - _managerVehicle = NULL; - _missionManager = NULL; + _managerVehicle = nullptr; + _missionManager = nullptr; } _managerVehicle = managerVehicle; @@ -2056,7 +2056,7 @@ VisualMissionItem* MissionController::currentPlanViewItem(void) const void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force) { if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) { - _currentPlanViewItem = NULL; + _currentPlanViewItem = nullptr; _currentPlanViewIndex = -1; for (int i = 0; i < _visualItems->count(); i++) { VisualMissionItem* pVI = qobject_cast(_visualItems->get(i)); diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index 6fa6e19efba2e9ec37dbe9ade2db2c656d7a3709..abe5ac741ee43935d119d8be1e32edaa868c715b 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -40,7 +40,7 @@ class MissionController : public PlanElementController Q_OBJECT public: - MissionController(PlanMasterController* masterController, QObject* parent = NULL); + MissionController(PlanMasterController* masterController, QObject* parent = nullptr); ~MissionController(); typedef struct _MissionFlightStatus_t { diff --git a/src/MissionManager/MissionControllerManagerTest.cc b/src/MissionManager/MissionControllerManagerTest.cc index 22669624f64975d06918a33bde72759aeb127863..cdb6ef60fec27711410412482fcc5b559365f885 100644 --- a/src/MissionManager/MissionControllerManagerTest.cc +++ b/src/MissionManager/MissionControllerManagerTest.cc @@ -21,7 +21,7 @@ MissionControllerManagerTest::MissionControllerManagerTest(void) void MissionControllerManagerTest::cleanup(void) { delete _multiSpyMissionManager; - _multiSpyMissionManager = NULL; + _multiSpyMissionManager = nullptr; UnitTest::cleanup(); } diff --git a/src/MissionManager/MissionControllerTest.cc b/src/MissionManager/MissionControllerTest.cc index b6b4793c986c890b73e172f3929b61459b9d0609..29d3f2c9c75ca5731933e1eb108ab9893991b797 100644 --- a/src/MissionManager/MissionControllerTest.cc +++ b/src/MissionManager/MissionControllerTest.cc @@ -18,9 +18,9 @@ #include "AppSettings.h" MissionControllerTest::MissionControllerTest(void) - : _multiSpyMissionController(NULL) - , _multiSpyMissionItem(NULL) - , _missionController(NULL) + : _multiSpyMissionController(nullptr) + , _multiSpyMissionItem(nullptr) + , _missionController(nullptr) { } @@ -28,13 +28,13 @@ MissionControllerTest::MissionControllerTest(void) void MissionControllerTest::cleanup(void) { delete _masterController; - _masterController = NULL; + _masterController = nullptr; delete _multiSpyMissionController; - _multiSpyMissionController = NULL; + _multiSpyMissionController = nullptr; delete _multiSpyMissionItem; - _multiSpyMissionItem = NULL; + _multiSpyMissionItem = nullptr; MissionControllerManagerTest::cleanup(); } diff --git a/src/MissionManager/MissionItem.h b/src/MissionManager/MissionItem.h index fb8cab6d98f18251f3954f377776b34c4c6944be..5e44bfa40e857df910a62790a1cba39bba860234 100644 --- a/src/MissionManager/MissionItem.h +++ b/src/MissionManager/MissionItem.h @@ -38,7 +38,7 @@ class MissionItem : public QObject Q_OBJECT public: - MissionItem(QObject* parent = NULL); + MissionItem(QObject* parent = nullptr); MissionItem(int sequenceNumber, MAV_CMD command, @@ -52,9 +52,9 @@ public: double param7, bool autoContinue, bool isCurrentItem, - QObject* parent = NULL); + QObject* parent = nullptr); - MissionItem(const MissionItem& other, QObject* parent = NULL); + MissionItem(const MissionItem& other, QObject* parent = nullptr); ~MissionItem(); diff --git a/src/MissionManager/MissionItemTest.cc b/src/MissionManager/MissionItemTest.cc index cac8d3bb5b645baedace6e44a127274b972d2001..e211f328ef3b9932c21e69ecdabaca619ae70c0f 100644 --- a/src/MissionManager/MissionItemTest.cc +++ b/src/MissionManager/MissionItemTest.cc @@ -28,7 +28,7 @@ const size_t MissionItemTest::_cTestCases = sizeof(_rgTestCases)/sizeof(_rgTestC #endif MissionItemTest::MissionItemTest(void) - : _offlineVehicle(NULL) + : _offlineVehicle(nullptr) { } @@ -282,7 +282,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void) { // We specifically test SimpleMissionItem loading as well since it has additional // signalling which can affect values. - SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, NULL); + SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, nullptr); QString testString("10\t0\t3\t80\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n"); QTextStream testStream(&testString, QIODevice::ReadOnly); @@ -452,7 +452,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void) // We specifically test SimpleMissionItem loading as well since it has additional // signalling which can affect values. - SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, NULL); + SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, nullptr); QString errorString; QJsonArray coordinateArray; QJsonObject jsonObject; diff --git a/src/MissionManager/MissionManagerTest.cc b/src/MissionManager/MissionManagerTest.cc index f354ee39480dd31e96bb05334938b221e99dcb1b..f94dc11445fa8553999a9c0d0fd1788835b8aa21 100644 --- a/src/MissionManager/MissionManagerTest.cc +++ b/src/MissionManager/MissionManagerTest.cc @@ -35,7 +35,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f QList missionItems; // Editor has a home position item on the front, so we do the same - MissionItem* homeItem = new MissionItem(NULL /* Vehicle */, this); + MissionItem* homeItem = new MissionItem(nullptr /* Vehicle */, this); homeItem->setCommand(MAV_CMD_NAV_WAYPOINT); homeItem->setParam5(47.3769); homeItem->setParam6(8.549444); diff --git a/src/MissionManager/MissionSettingsItem.cc b/src/MissionManager/MissionSettingsItem.cc index 912e67fc5737efac2db58528aeff4f49376ff7f8..e816d9de645f813b971770ab845e2d8a15ef285a 100644 --- a/src/MissionManager/MissionSettingsItem.cc +++ b/src/MissionManager/MissionSettingsItem.cc @@ -40,7 +40,7 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject _editorQml = "qrc:/qml/MissionSettingsEditor.qml"; if (_metaDataMap.isEmpty()) { - _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/MissionSettings.FactMetaData.json"), NULL /* metaDataParent */); + _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/MissionSettings.FactMetaData.json"), nullptr /* metaDataParent */); } _plannedHomePositionAltitudeFact.setMetaData (_metaDataMap[_plannedHomePositionAltitudeName]); @@ -163,7 +163,7 @@ void MissionSettingsItem::appendMissionItems(QList& items, QObject bool MissionSettingsItem::addMissionEndAction(QList& items, int seqNum, QObject* missionItemParent) { - MissionItem* item = NULL; + MissionItem* item = nullptr; // IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings diff --git a/src/MissionManager/MissionSettingsTest.cc b/src/MissionManager/MissionSettingsTest.cc index 4688d5afbd2daf6cc7f7450df960aacb815a0ec0..28b2a710ba4d8f269117d3f25db110e5779332c2 100644 --- a/src/MissionManager/MissionSettingsTest.cc +++ b/src/MissionManager/MissionSettingsTest.cc @@ -13,7 +13,7 @@ #include "SettingsManager.h" MissionSettingsTest::MissionSettingsTest(void) - : _settingsItem(NULL) + : _settingsItem(nullptr) { } diff --git a/src/MissionManager/PlanElementController.h b/src/MissionManager/PlanElementController.h index 078f218a2f0b81a091a902a44ac74329fd99cf84..3d93ecbd366887c106691b7a7b9035566b6b8fa0 100644 --- a/src/MissionManager/PlanElementController.h +++ b/src/MissionManager/PlanElementController.h @@ -24,7 +24,7 @@ class PlanElementController : public QObject Q_OBJECT public: - PlanElementController(PlanMasterController* masterController, QObject* parent = NULL); + PlanElementController(PlanMasterController* masterController, QObject* parent = nullptr); ~PlanElementController(); Q_PROPERTY(bool supported READ supported NOTIFY supportedChanged) ///< true: Element is supported by Vehicle diff --git a/src/MissionManager/PlanManager.cc b/src/MissionManager/PlanManager.cc index 833c2f262f128028bbbe5dea2b8b344e2f2a34fe..f137124e62b1c87630f43c87a96bd1daba887271 100644 --- a/src/MissionManager/PlanManager.cc +++ b/src/MissionManager/PlanManager.cc @@ -24,8 +24,8 @@ QGC_LOGGING_CATEGORY(PlanManagerLog, "PlanManagerLog") PlanManager::PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType) : _vehicle (vehicle) , _planType (planType) - , _dedicatedLink (NULL) - , _ackTimeoutTimer (NULL) + , _dedicatedLink (nullptr) + , _ackTimeoutTimer (nullptr) , _expectedAck (AckNone) , _transactionInProgress (TransactionNone) , _resumeMission (false) diff --git a/src/MissionManager/PlanMasterController.h b/src/MissionManager/PlanMasterController.h index 344465a1ae64cd35fff8892ce0b3535f451a8ee8..fed93869e61c0911a1b0dab2219e1b341683eefa 100644 --- a/src/MissionManager/PlanMasterController.h +++ b/src/MissionManager/PlanMasterController.h @@ -26,7 +26,7 @@ class PlanMasterController : public QObject Q_OBJECT public: - PlanMasterController(QObject* parent = NULL); + PlanMasterController(QObject* parent = nullptr); ~PlanMasterController(); Q_PROPERTY(MissionController* missionController READ missionController CONSTANT) diff --git a/src/MissionManager/PlanMasterControllerTest.cc b/src/MissionManager/PlanMasterControllerTest.cc index eae62cb08b992f1f1ec1ec5030fdae606f7384f6..64ee593fcdfb7fb58079482da4d106b8522c5064 100644 --- a/src/MissionManager/PlanMasterControllerTest.cc +++ b/src/MissionManager/PlanMasterControllerTest.cc @@ -17,7 +17,7 @@ #include "AppSettings.h" PlanMasterControllerTest::PlanMasterControllerTest(void) - : _masterController(NULL) + : _masterController(nullptr) { } @@ -33,7 +33,7 @@ void PlanMasterControllerTest::init(void) void PlanMasterControllerTest::cleanup(void) { delete _masterController; - _masterController = NULL; + _masterController = nullptr; UnitTest::cleanup(); } diff --git a/src/MissionManager/QGCFenceCircle.h b/src/MissionManager/QGCFenceCircle.h index d42a8f356556c730718dcb96d334d0f40db85e35..6454e51e70a97ec1ca7520b8e5860d2416ea2234 100644 --- a/src/MissionManager/QGCFenceCircle.h +++ b/src/MissionManager/QGCFenceCircle.h @@ -17,9 +17,9 @@ class QGCFenceCircle : public QGCMapCircle Q_OBJECT public: - QGCFenceCircle(QObject* parent = NULL); - QGCFenceCircle(const QGeoCoordinate& center, double radius, bool inclusion, QObject* parent = NULL); - QGCFenceCircle(const QGCFenceCircle& other, QObject* parent = NULL); + QGCFenceCircle(QObject* parent = nullptr); + QGCFenceCircle(const QGeoCoordinate& center, double radius, bool inclusion, QObject* parent = nullptr); + QGCFenceCircle(const QGCFenceCircle& other, QObject* parent = nullptr); const QGCFenceCircle& operator=(const QGCFenceCircle& other); diff --git a/src/MissionManager/QGCFencePolygon.h b/src/MissionManager/QGCFencePolygon.h index fb79ca4837a22b3cdb2fede6b5791afd0d930838..7279cbf8bc2cab1a2311344257d03aea24a6c2f7 100644 --- a/src/MissionManager/QGCFencePolygon.h +++ b/src/MissionManager/QGCFencePolygon.h @@ -17,8 +17,8 @@ class QGCFencePolygon : public QGCMapPolygon Q_OBJECT public: - QGCFencePolygon(bool inclusion, QObject* parent = NULL); - QGCFencePolygon(const QGCFencePolygon& other, QObject* parent = NULL); + QGCFencePolygon(bool inclusion, QObject* parent = nullptr); + QGCFencePolygon(const QGCFencePolygon& other, QObject* parent = nullptr); const QGCFencePolygon& operator=(const QGCFencePolygon& other); diff --git a/src/MissionManager/QGCMapPolyline.h b/src/MissionManager/QGCMapPolyline.h index 08389a0416eda69e18996b0e2515e129206dc272..78254c7df368cbd047e417b164c49fb0306355d8 100644 --- a/src/MissionManager/QGCMapPolyline.h +++ b/src/MissionManager/QGCMapPolyline.h @@ -20,8 +20,8 @@ class QGCMapPolyline : public QObject Q_OBJECT public: - QGCMapPolyline(QObject* parent = NULL); - QGCMapPolyline(const QGCMapPolyline& other, QObject* parent = NULL); + QGCMapPolyline(QObject* parent = nullptr); + QGCMapPolyline(const QGCMapPolyline& other, QObject* parent = nullptr); const QGCMapPolyline& operator=(const QGCMapPolyline& other); diff --git a/src/MissionManager/RallyPoint.cc b/src/MissionManager/RallyPoint.cc index 753ad3ec3ca188a2ad8578228869f520f59cb23c..51847e3b1d8e41342c04efa331f00f5fc2f1567d 100644 --- a/src/MissionManager/RallyPoint.cc +++ b/src/MissionManager/RallyPoint.cc @@ -64,7 +64,7 @@ RallyPoint::~RallyPoint() void RallyPoint::_factSetup(void) { if (_metaDataMap.isEmpty()) { - _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/RallyPoint.FactMetaData.json"), NULL /* metaDataParent */); + _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/RallyPoint.FactMetaData.json"), nullptr /* metaDataParent */); } _longitudeFact.setMetaData(_metaDataMap[_longitudeFactName]); diff --git a/src/MissionManager/RallyPoint.h b/src/MissionManager/RallyPoint.h index 9133716597fbd830eb695e57bede6a2a65b52750..5868118232797b84f796591e7cf071b038e5c23d 100644 --- a/src/MissionManager/RallyPoint.h +++ b/src/MissionManager/RallyPoint.h @@ -22,8 +22,8 @@ class RallyPoint : public QObject Q_OBJECT public: - RallyPoint(const QGeoCoordinate& coordinate, QObject* parent = NULL); - RallyPoint(const RallyPoint& other, QObject* parent = NULL); + RallyPoint(const QGeoCoordinate& coordinate, QObject* parent = nullptr); + RallyPoint(const RallyPoint& other, QObject* parent = nullptr); ~RallyPoint(); diff --git a/src/MissionManager/RallyPointController.cc b/src/MissionManager/RallyPointController.cc index 506024f433b8a89c43d5a77424c186eb01d4c4dd..732d080b718d3055a21c63ae5be88fe527480b7c 100644 --- a/src/MissionManager/RallyPointController.cc +++ b/src/MissionManager/RallyPointController.cc @@ -37,7 +37,7 @@ RallyPointController::RallyPointController(PlanMasterController* masterControlle : PlanElementController(masterController, parent) , _rallyPointManager(_managerVehicle->rallyPointManager()) , _dirty(false) - , _currentRallyPoint(NULL) + , _currentRallyPoint(nullptr) , _itemsRequested(false) { connect(&_points, &QmlObjectListModel::countChanged, this, &RallyPointController::_updateContainsItems); @@ -55,8 +55,8 @@ void RallyPointController::managerVehicleChanged(Vehicle* managerVehicle) if (_managerVehicle) { _rallyPointManager->disconnect(this); _managerVehicle->disconnect(this); - _managerVehicle = NULL; - _rallyPointManager = NULL; + _managerVehicle = nullptr; + _rallyPointManager = nullptr; } _managerVehicle = managerVehicle; @@ -138,7 +138,7 @@ void RallyPointController::removeAll(void) { _points.clearAndDeleteContents(); setDirty(true); - setCurrentRallyPoint(NULL); + setCurrentRallyPoint(nullptr); } void RallyPointController::removeAllFromVehicle(void) @@ -268,7 +268,7 @@ void RallyPointController::removePoint(QObject* rallyPoint) newIndex = qMax(newIndex, 0); setCurrentRallyPoint(_points[newIndex]); } else { - setCurrentRallyPoint(NULL); + setCurrentRallyPoint(nullptr); } } @@ -282,7 +282,7 @@ void RallyPointController::setCurrentRallyPoint(QObject* rallyPoint) void RallyPointController::_setFirstPointCurrent(void) { - setCurrentRallyPoint(_points.count() ? _points[0] : NULL); + setCurrentRallyPoint(_points.count() ? _points[0] : nullptr); } bool RallyPointController::containsItems(void) const diff --git a/src/MissionManager/RallyPointController.h b/src/MissionManager/RallyPointController.h index 95d1f0f13b672c517b70d479730f6429fa071506..7543642edce71ae5f4cbae859debffd4eca478f5 100644 --- a/src/MissionManager/RallyPointController.h +++ b/src/MissionManager/RallyPointController.h @@ -26,7 +26,7 @@ class RallyPointController : public PlanElementController Q_OBJECT public: - RallyPointController(PlanMasterController* masterController, QObject* parent = NULL); + RallyPointController(PlanMasterController* masterController, QObject* parent = nullptr); ~RallyPointController(); Q_PROPERTY(QmlObjectListModel* points READ points CONSTANT) diff --git a/src/MissionManager/Section.h b/src/MissionManager/Section.h index 638f22be6c761f19769986ac052e708f6b648aee..9e033c57c5a2899f67ab4c5a823e627757b70017 100644 --- a/src/MissionManager/Section.h +++ b/src/MissionManager/Section.h @@ -21,7 +21,7 @@ class Section : public QObject Q_OBJECT public: - Section(Vehicle* vehicle, QObject* parent = NULL) + Section(Vehicle* vehicle, QObject* parent = nullptr) : QObject(parent) , _vehicle(vehicle) { diff --git a/src/MissionManager/SectionTest.cc b/src/MissionManager/SectionTest.cc index a959712a22095f59a7a6dfbed0b606ab2fbd7cac..1c8a467579ea9dae72b95048fa3ef992bf419ca5 100644 --- a/src/MissionManager/SectionTest.cc +++ b/src/MissionManager/SectionTest.cc @@ -11,7 +11,7 @@ #include "SurveyComplexItem.h" SectionTest::SectionTest(void) - : _simpleItem(NULL) + : _simpleItem(nullptr) { } @@ -48,7 +48,7 @@ void SectionTest::cleanup(void) void SectionTest::_createSpy(Section* section, MultiSignalSpy** sectionSpy) { - *sectionSpy = NULL; + *sectionSpy = nullptr; MultiSignalSpy* spy = new MultiSignalSpy(); QCOMPARE(spy->init(section, rgSectionSignals, cSectionSignals), true); *sectionSpy = spy; diff --git a/src/MissionManager/SpeedSection.cc b/src/MissionManager/SpeedSection.cc index 90e49b5b2368442ecbf5b47d3f305114dd9667ea..a30f17da3b0103951e80f146478af108d192ce84 100644 --- a/src/MissionManager/SpeedSection.cc +++ b/src/MissionManager/SpeedSection.cc @@ -24,7 +24,7 @@ SpeedSection::SpeedSection(Vehicle* vehicle, QObject* parent) , _flightSpeedFact (0, _flightSpeedName, FactMetaData::valueTypeDouble) { if (_metaDataMap.isEmpty()) { - _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/SpeedSection.FactMetaData.json"), NULL /* metaDataParent */); + _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/SpeedSection.FactMetaData.json"), nullptr /* metaDataParent */); } double flightSpeed = 0; diff --git a/src/MissionManager/SpeedSection.h b/src/MissionManager/SpeedSection.h index ad0c66fde1763ec118ddaa6d52633a8e0ce4722d..31177325f7538a882bd8de7b4b14684cf10224c7 100644 --- a/src/MissionManager/SpeedSection.h +++ b/src/MissionManager/SpeedSection.h @@ -18,7 +18,7 @@ class SpeedSection : public Section Q_OBJECT public: - SpeedSection(Vehicle* vehicle, QObject* parent = NULL); + SpeedSection(Vehicle* vehicle, QObject* parent = nullptr); Q_PROPERTY(bool specifyFlightSpeed READ specifyFlightSpeed WRITE setSpecifyFlightSpeed NOTIFY specifyFlightSpeedChanged) Q_PROPERTY(Fact* flightSpeed READ flightSpeed CONSTANT) diff --git a/src/MissionManager/SpeedSectionTest.cc b/src/MissionManager/SpeedSectionTest.cc index a52442c2761a6f2e069d3987d4439af2f34563f7..94425a078c97d7e54fe415567532c26eb9cc3413 100644 --- a/src/MissionManager/SpeedSectionTest.cc +++ b/src/MissionManager/SpeedSectionTest.cc @@ -10,9 +10,9 @@ #include "SpeedSectionTest.h" SpeedSectionTest::SpeedSectionTest(void) - : _spySpeed(NULL) - , _spySection(NULL) - , _speedSection(NULL) + : _spySpeed(nullptr) + , _spySection(nullptr) + , _speedSection(nullptr) { } @@ -39,7 +39,7 @@ void SpeedSectionTest::cleanup(void) void SpeedSectionTest::_createSpy(SpeedSection* speedSection, MultiSignalSpy** speedSpy) { - *speedSpy = NULL; + *speedSpy = nullptr; MultiSignalSpy* spy = new MultiSignalSpy(); QCOMPARE(spy->init(speedSection, rgSpeedSignals, cSpeedSignals), true); *speedSpy = spy; @@ -193,7 +193,7 @@ void SpeedSectionTest::_testScanForSection(void) double flightSpeed = 10.123456; MissionItem validSpeedItem(0, MAV_CMD_DO_CHANGE_SPEED, MAV_FRAME_MISSION, _offlineVehicle->multiRotor() ? 1 : 0, flightSpeed, -1, 0, 0, 0, 0, true, false); - SimpleMissionItem simpleItem(_offlineVehicle, false /* flyView */, validSpeedItem, NULL); + SimpleMissionItem simpleItem(_offlineVehicle, false /* flyView */, validSpeedItem, nullptr); MissionItem& simpleMissionItem = simpleItem.missionItem(); visualItems.append(&simpleItem); scanIndex = 0; @@ -264,7 +264,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(_offlineVehicle, false /* flyView */, waypointMissionItem, NULL); + SimpleMissionItem simpleWaypointItem(_offlineVehicle, false /* flyView */, waypointMissionItem, nullptr); simpleMissionItem = validSpeedItem; visualItems.append(&simpleWaypointItem); visualItems.append(&simpleMissionItem); diff --git a/src/MissionManager/SurveyComplexItemTest.cc b/src/MissionManager/SurveyComplexItemTest.cc index 0666bda98cc7d358eec1de52ebebf4334197bee3..6a258137963e8f9f444ddef4c3724d0229014866 100644 --- a/src/MissionManager/SurveyComplexItemTest.cc +++ b/src/MissionManager/SurveyComplexItemTest.cc @@ -11,7 +11,7 @@ #include "QGCApplication.h" SurveyComplexItemTest::SurveyComplexItemTest(void) - : _offlineVehicle(NULL) + : _offlineVehicle(nullptr) { _polyPoints << QGeoCoordinate(47.633550640000003, -122.08982199) << QGeoCoordinate(47.634129020000003, -122.08887249) << QGeoCoordinate(47.633619320000001, -122.08811074) << QGeoCoordinate(47.633189139999999, -122.08900124); diff --git a/src/MissionManager/TransectStyleComplexItemTest.cc b/src/MissionManager/TransectStyleComplexItemTest.cc index e2ccd5bd3b289de391971c109faa667ece710660..08ee329cd4550ea39e05a37c5452f0de709128e3 100644 --- a/src/MissionManager/TransectStyleComplexItemTest.cc +++ b/src/MissionManager/TransectStyleComplexItemTest.cc @@ -11,7 +11,7 @@ #include "QGCApplication.h" TransectStyleComplexItemTest::TransectStyleComplexItemTest(void) - : _offlineVehicle(NULL) + : _offlineVehicle(nullptr) { _polygonVertices << QGeoCoordinate(47.633550640000003, -122.08982199) << QGeoCoordinate(47.634129020000003, -122.08887249) diff --git a/src/MissionManager/TransectStyleComplexItemTest.h b/src/MissionManager/TransectStyleComplexItemTest.h index b85cb478658c559d63aa29663c91a09ecd0df411..2f62e28ffe69d7d97f9b0983d975b9387c7f9f42 100644 --- a/src/MissionManager/TransectStyleComplexItemTest.h +++ b/src/MissionManager/TransectStyleComplexItemTest.h @@ -83,7 +83,7 @@ class TransectStyleItem : public TransectStyleComplexItem Q_OBJECT public: - TransectStyleItem(Vehicle* vehicle, QObject* parent = NULL); + TransectStyleItem(Vehicle* vehicle, QObject* parent = nullptr); // Overrides from ComplexMissionItem QString mapVisualQML (void) const final { return QString(); } diff --git a/src/MissionManager/VisualMissionItemTest.cc b/src/MissionManager/VisualMissionItemTest.cc index 8a6e235ceaeacb6499c174b5b05895ae938aff3a..beb9cae0dea74d43e596b27bf14dd9b868df4a76 100644 --- a/src/MissionManager/VisualMissionItemTest.cc +++ b/src/MissionManager/VisualMissionItemTest.cc @@ -12,7 +12,7 @@ #include "QGCApplication.h" VisualMissionItemTest::VisualMissionItemTest(void) - : _offlineVehicle(NULL) + : _offlineVehicle(nullptr) { } @@ -60,7 +60,7 @@ void VisualMissionItemTest::cleanup(void) void VisualMissionItemTest::_createSpy(SimpleMissionItem* simpleItem, MultiSignalSpy** visualSpy) { - *visualSpy = NULL; + *visualSpy = nullptr; MultiSignalSpy* spy = new MultiSignalSpy(); QCOMPARE(spy->init(simpleItem, rgVisualItemSignals, cVisualItemSignals), true); *visualSpy = spy; diff --git a/src/PositionManager/PositionManager.cpp b/src/PositionManager/PositionManager.cpp index 5de73d0f6e715a455e19de612c91dfbc486469e6..99620d2050f1995d759358f136d63739cb6b1b53 100644 --- a/src/PositionManager/PositionManager.cpp +++ b/src/PositionManager/PositionManager.cpp @@ -15,10 +15,10 @@ QGCPositionManager::QGCPositionManager(QGCApplication* app, QGCToolbox* toolbox) : QGCTool (app, toolbox) , _updateInterval (0) , _gcsHeading (NAN) - , _currentSource (NULL) - , _defaultSource (NULL) - , _nmeaSource (NULL) - , _simulatedSource (NULL) + , _currentSource (nullptr) + , _defaultSource (nullptr) + , _nmeaSource (nullptr) + , _simulatedSource (nullptr) { } diff --git a/src/PositionManager/SimulatedPosition.cc b/src/PositionManager/SimulatedPosition.cc index 8a345a49f3549c39aff26977caebdded89d53cc8..da8157b217c7b64c6c73b5addbc7c81327e7a91d 100644 --- a/src/PositionManager/SimulatedPosition.cc +++ b/src/PositionManager/SimulatedPosition.cc @@ -16,7 +16,7 @@ SimulatedPosition::simulated_motion_s SimulatedPosition::_simulated_motion[5] = {{0,250},{0,0},{0, -250},{-250, 0},{0,0}}; SimulatedPosition::SimulatedPosition() - : QGeoPositionInfoSource(NULL), + : QGeoPositionInfoSource(nullptr), lat_int(47.3977420*1e7), lon_int(8.5455941*1e7), _step_cnt(0),