diff --git a/.travis.yml b/.travis.yml index c4b61d6884abc652808b73b510f37c8ea8573aa9..a4a2e7f69791d37ad837641d09c47ad907808b5f 100644 --- a/.travis.yml +++ b/.travis.yml @@ -241,6 +241,7 @@ deploy: # deploy tagged installers to s3 latest/ - provider: s3 + edge: true # Use V2 provider to work around V1 bug access_key_id: AKIAIVORNALE7NHD3T6Q secret_access_key: secure: BsLXeXUPsCJdX4tawrDnO8OFK5Hk4kzlDTiyH93En6TbjUargVAWDMcHVj7TUhr7+3Tao1W1zb0G4SJe9kHv+jrky0yE72KvoG3YAON0VXWKizxBAKkgHE2RxSTNAwDeKbi2G6YJfNDescBBfX7zEohShdXglQu7CGaUQKRaiI4= @@ -283,6 +284,7 @@ deploy: on: tags: true condition: $CONFIG = installer + condition: $SPEC != macx-clang # GitHub OSX deploy broken due to travis problem notifications: webhooks: diff --git a/ChangeLog.md b/ChangeLog.md index 23e1366fccc0c7c2f28457ccf1a3b422c3cfc3c5..096f20600ac409a7e364dd1b7cda16f3e9d3a8f4 100644 --- a/ChangeLog.md +++ b/ChangeLog.md @@ -8,6 +8,14 @@ Note: This file only contains high level features or important fixes. ## 4.0 +### 4.0.3 - Not yet released + + +### 4.0.3 - Not yet released + +* Plan: Add setting for takeoff item not required +* Plan: Takeoff item must be added prior to allowing other item types to enable + ### 4.0.2 - Stable * Fix Mavlink V2 protocol negotation based on capability bits @@ -18,6 +26,8 @@ Note: This file only contains high level features or important fixes. * Fix ArduPilot current mission item tracking in Fly view * Fix ADSB vehicle display +* Fix map positioning bug in Plan view +* Fix Windows 0xcc000007b startup error causes by incorrect VC runtimes being installed. ### 4.0.0 diff --git a/QGCSetup.pri b/QGCSetup.pri index e6546f6af289e052acb87135e03e157a30595dac..9ecb1435eeafa118a03a7184e1ef5a33bc0066b5 100644 --- a/QGCSetup.pri +++ b/QGCSetup.pri @@ -79,8 +79,6 @@ WindowsBuild { # Copy Visual Studio DLLs # Note that this is only done for release because the debugging versions of these DLLs cannot be redistributed. QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$BASEDIR\\deploy\\msvcp140.dll\" \"$$DESTDIR_WIN\" - QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$BASEDIR\\deploy\\msvcp140_1.dll\" \"$$DESTDIR_WIN\" - QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$BASEDIR\\deploy\\msvcp140_2.dll\" \"$$DESTDIR_WIN\" QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$BASEDIR\\deploy\\vcruntime140.dll\" \"$$DESTDIR_WIN\" } diff --git a/deploy/msvcp140.dll b/deploy/msvcp140.dll index 6ca27d5150e0faaf4a32ee3224332cdea5b61829..98313d4c125307dbc5784b5a329c7d113183d3c8 100644 Binary files a/deploy/msvcp140.dll and b/deploy/msvcp140.dll differ diff --git a/deploy/msvcp140_1.dll b/deploy/msvcp140_1.dll deleted file mode 100644 index 64f090daf6d5d06dcc2991c6469ffe23964b59c3..0000000000000000000000000000000000000000 Binary files a/deploy/msvcp140_1.dll and /dev/null differ diff --git a/deploy/msvcp140_2.dll b/deploy/msvcp140_2.dll deleted file mode 100644 index 682fd794200adce7f9a6184ea4cfaf019702af1f..0000000000000000000000000000000000000000 Binary files a/deploy/msvcp140_2.dll and /dev/null differ diff --git a/deploy/qgroundcontrol_installer.nsi b/deploy/qgroundcontrol_installer.nsi index e69741bceefa3da8313b232f0f6721cbf2971fa1..b3a8a3c83e9d92ae96814a74afd27c726379fdfb 100644 --- a/deploy/qgroundcontrol_installer.nsi +++ b/deploy/qgroundcontrol_installer.nsi @@ -71,8 +71,7 @@ check64BitUninstall: StrCmp $R0 "" doInstall doUninstall: - DetailPrint "Uninstalling previous version..." - ExecWait "$R0 /S -LEAVE_DATA=1" + DetailPrint "Uninstalling previous version..." ExecWait "$R0 /S -LEAVE_DATA=1 _?=$INSTDIR" IntCmp $0 0 doInstall MessageBox MB_OK|MB_ICONEXCLAMATION \ diff --git a/deploy/vcruntime140.dll b/deploy/vcruntime140.dll index 3e49417f82c57023b2fd59defeb87e8b2ffea620..34a0e72504776f90526966db1e3e9d382674d613 100644 Binary files a/deploy/vcruntime140.dll and b/deploy/vcruntime140.dll differ diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 419561db40dcc03399b1f72854777a5d0f5cf027..0d967c4cc6398b609b327e02e1e3fb62866cb2f8 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -482,14 +482,13 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu void PX4FirmwarePlugin::startMission(Vehicle* vehicle) { - if (_setFlightModeAndValidate(vehicle, missionFlightMode())) { if (!_armVehicleAndValidate(vehicle)) { qgcApp()->showMessage(tr("Unable to start mission: Vehicle rejected arming.")); return; } } else { - qgcApp()->showMessage(tr("Unable to start mission: Vehicle not ready.")); + qgcApp()->showMessage(tr("Unable to start mission: Vehicle not changing to %1 flight mode.").arg(missionFlightMode())); } } diff --git a/src/FlightDisplay/PreFlightSensorsHealthCheck.qml b/src/FlightDisplay/PreFlightSensorsHealthCheck.qml index 1d04ad1bce0522a66b8ee70ea1808a5280c53a35..e5e4a2a37886890c4ed13b8b0cd9b32226b88533 100644 --- a/src/FlightDisplay/PreFlightSensorsHealthCheck.qml +++ b/src/FlightDisplay/PreFlightSensorsHealthCheck.qml @@ -17,7 +17,7 @@ PreFlightCheckButton { name: qsTr("Sensors") telemetryFailure: _unhealthySensors & _allCheckedSensors - property int _unhealthySensors: activeVehicle ? activeVehicle.sensorsUnhealthyBits : 0 + property int _unhealthySensors: activeVehicle ? activeVehicle.sensorsUnhealthyBits : 1 property int _allCheckedSensors: Vehicle.SysStatusSensor3dMag | Vehicle.SysStatusSensor3dAccel | Vehicle.SysStatusSensor3dGyro | diff --git a/src/FlightMap/Widgets/MapFitFunctions.qml b/src/FlightMap/Widgets/MapFitFunctions.qml index b8197994f988a8b5afd1be00bff0c015b17059b5..ac8bfa8cf88227304e3b294cbe60a4f154b80670 100644 --- a/src/FlightMap/Widgets/MapFitFunctions.qml +++ b/src/FlightMap/Widgets/MapFitFunctions.qml @@ -41,7 +41,7 @@ Item { /// Normalize longitude to range: 0 to 360, W to E function normalizeLon(lon) { - return lon + 180.0 + return lon + 180.0 } /// Fits the visible region of the map to inclues all of the specified coordinates. If no coordinates @@ -64,12 +64,12 @@ Item { for (var i = 1; i < coordList.length; i++) { var lat = coordList[i].latitude var lon = coordList[i].longitude - if (isNaN(lat) || lat == 0 || isNan(lon) || lon == 0) { + if (isNaN(lat) || lat == 0 || isNaN(lon) || lon == 0) { // Be careful of invalid coords which can happen when items are not yet complete continue } lat = normalizeLat(lat) - lon = normalizeLon(lat) + lon = normalizeLon(lon) north = Math.max(north, lat) south = Math.min(south, lat) east = Math.max(east, lon) @@ -77,8 +77,8 @@ Item { } // Expand the coordinate bounding rect to make room for the tools around the edge of the map - var latDegreesPerPixel = (north - south) / mapFitViewport.width - var lonDegreesPerPixel = (east - west) / mapFitViewport.height + var latDegreesPerPixel = (north - south) / mapFitViewport.height + var lonDegreesPerPixel = (east - west) / mapFitViewport.width north = Math.min(north + (mapFitViewport.y * latDegreesPerPixel), 180) south = Math.max(south - ((map.height - mapFitViewport.bottom) * latDegreesPerPixel), 0) west = Math.max(west - (mapFitViewport.x * lonDegreesPerPixel), 0) @@ -94,7 +94,6 @@ Item { var topLeftCoord = QtPositioning.coordinate(north - 90.0, west - 180.0) var bottomRightCoord = QtPositioning.coordinate(south - 90.0, east - 180.0) map.setVisibleRegion(QtPositioning.rectangle(topLeftCoord, bottomRightCoord)) - } function addMissionItemCoordsForFit(coordList) { diff --git a/src/MissionManager/CameraSectionTest.cc b/src/MissionManager/CameraSectionTest.cc index 6f9497a902b2f52b86e235766a21dfced1166394..f6dfb63493f978686f152b99dc00c2d5c380c490 100644 --- a/src/MissionManager/CameraSectionTest.cc +++ b/src/MissionManager/CameraSectionTest.cc @@ -592,7 +592,7 @@ void CameraSectionTest::_testScanForGimbalSection(void) // Check for a scan success - SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_masterController, false /* flyView */, this); + SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); newValidGimbalItem->missionItem() = _validGimbalItem->missionItem(); visualItems.append(newValidGimbalItem); scanIndex = 0; @@ -676,7 +676,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void) // Check for a scan success - SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_masterController, false /* flyView */, this); + SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); newValidCameraModeItem->missionItem() = _validCameraPhotoModeItem->missionItem(); visualItems.append(newValidCameraModeItem); scanIndex = 0; @@ -735,7 +735,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void) Mission Param #3 Number of images to capture total - 0 for unlimited capture */ - SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_masterController, false /* flyView */, this); + SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); newValidTimeItem->missionItem() = _validTimeItem->missionItem(); visualItems.append(newValidTimeItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -776,7 +776,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) Mission Param #7 Empty */ - SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_masterController, false /* flyView */, this); + SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); newValidDistanceItem->missionItem() = _validDistanceItem->missionItem(); visualItems.append(newValidDistanceItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -862,7 +862,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) Mission Param #3 Reserved */ - SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_masterController, false /* flyView */, this); + SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); newValidStartVideoItem->missionItem() = _validStartVideoItem->missionItem(); visualItems.append(newValidStartVideoItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -898,7 +898,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void) Mission Param #1 Reserved (Set to 0) */ - SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_masterController, false /* flyView */, this); + SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); newValidStopVideoItem->missionItem() = _validStopVideoItem->missionItem(); visualItems.append(newValidStopVideoItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -936,8 +936,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void) _commonScanTest(_cameraSection); - SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_masterController, false /* flyView */, this); - SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_masterController, false /* flyView */, this); + SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); + SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); newValidStopDistanceItem->missionItem() = _validStopDistanceItem->missionItem(); newValidStopTimeItem->missionItem() = _validStopTimeItem->missionItem(); visualItems.append(newValidStopDistanceItem); @@ -950,8 +950,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void) // Out of order commands - SimpleMissionItem validStopDistanceItem(_masterController, false /* flyView */, nullptr); - SimpleMissionItem validStopTimeItem(_masterController, false /* flyView */, nullptr); + SimpleMissionItem validStopDistanceItem(_masterController, false /* flyView */, false /* forLoad */, nullptr); + SimpleMissionItem validStopTimeItem(_masterController, false /* flyView */, false /* forLoad */, nullptr); validStopDistanceItem.missionItem() = _validStopDistanceItem->missionItem(); validStopTimeItem.missionItem() = _validStopTimeItem->missionItem(); visualItems.append(&validStopTimeItem); @@ -979,7 +979,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void) Mission Param #4 0 Unused sequence id */ - SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_masterController, false /* flyView */, this); + SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); newValidTakePhotoItem->missionItem() = _validTakePhotoItem->missionItem(); visualItems.append(newValidTakePhotoItem); QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true); @@ -1051,9 +1051,9 @@ void CameraSectionTest::_testScanForMultipleItems(void) // Camera action followed by gimbal/mode for (SimpleMissionItem* actionItem: rgActionItems) { for (SimpleMissionItem* cameraItem: rgCameraItems) { - SimpleMissionItem* item1 = new SimpleMissionItem(_masterController, false /* flyView */, this); + SimpleMissionItem* item1 = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); item1->missionItem() = actionItem->missionItem(); - SimpleMissionItem* item2 = new SimpleMissionItem(_masterController, false /* flyView */, this); + SimpleMissionItem* item2 = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); item2->missionItem() = cameraItem->missionItem(); visualItems.append(item1); visualItems.append(item2); @@ -1072,9 +1072,9 @@ void CameraSectionTest::_testScanForMultipleItems(void) // Gimbal/Mode followed by camera action for (SimpleMissionItem* actionItem: rgCameraItems) { for (SimpleMissionItem* cameraItem: rgActionItems) { - SimpleMissionItem* item1 = new SimpleMissionItem(_masterController, false /* flyView */, this); + SimpleMissionItem* item1 = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); item1->missionItem() = actionItem->missionItem(); - SimpleMissionItem* item2 = new SimpleMissionItem(_masterController, false /* flyView */, this); + SimpleMissionItem* item2 = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, this); item2->missionItem() = cameraItem->missionItem(); visualItems.append(item1); visualItems.append(item2); diff --git a/src/MissionManager/FWLandingPatternTest.cc b/src/MissionManager/FWLandingPatternTest.cc index 4ff6f3aa66b2dc82a7a704a7410802df2bee8cbd..ee969f0ffa203b7ae78642cec4d57316932c56ca 100644 --- a/src/MissionManager/FWLandingPatternTest.cc +++ b/src/MissionManager/FWLandingPatternTest.cc @@ -89,7 +89,7 @@ void FWLandingPatternTest::_testAppendSectionItems(void) QmlObjectListModel* simpleItems = new QmlObjectListModel(this); for (MissionItem* item: rgMissionItems) { - SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, simpleItems); + SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, simpleItems); simpleItem->missionItem() = *item; simpleItems->append(simpleItem); } @@ -110,7 +110,7 @@ void FWLandingPatternTest::_testAppendSectionItems(void) _fwItem->appendMissionItems(rgMissionItems, this); simpleItems = new QmlObjectListModel(this); for (MissionItem* item: rgMissionItems) { - SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, simpleItems); + SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, simpleItems); simpleItem->missionItem() = *item; simpleItems->append(simpleItem); } diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 5ab4302f09c4c80a74505c3426f24b92a0243626..5809910349cc7e15f499b1ef17e2bb6e675d1190 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -31,6 +31,7 @@ #include "KML.h" #include "QGCCorePlugin.h" #include "TakeoffMissionItem.h" +#include "PlanViewSettings.h" #define UPDATE_TIMEOUT 5000 ///< How often we check for bounding box changes @@ -62,12 +63,15 @@ MissionController::MissionController(PlanMasterController* masterController, QOb , _controllerVehicle (masterController->controllerVehicle()) , _managerVehicle (masterController->managerVehicle()) , _missionManager (masterController->managerVehicle()->missionManager()) + , _planViewSettings (qgcApp()->toolbox()->settingsManager()->planViewSettings()) , _appSettings (qgcApp()->toolbox()->settingsManager()->appSettings()) { _resetMissionFlightStatus(); _updateTimer.setSingleShot(true); connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout); + + connect(_planViewSettings->takeoffItemNotRequired(), &Fact::rawValueChanged, this, &MissionController::_takeoffItemNotRequiredChanged); } MissionController::~MissionController() @@ -337,7 +341,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, this); + SimpleMissionItem * newItem = new SimpleMissionItem(_masterController, _flyView, false /* forLoad */, this); newItem->setSequenceNumber(sequenceNumber); newItem->setCoordinate(coordinate); newItem->setCommand(command); @@ -651,7 +655,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec MissionSettingsItem* settingsItem = _addMissionSettings(visualItems); if (json.contains(_jsonPlannedHomePositionKey)) { - SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, visualItems); + SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */, visualItems); if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) { settingsItem->setInitialHomePositionFromUser(item->coordinate()); item->deleteLater(); @@ -687,11 +691,11 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec } const QJsonObject itemObject = itemValue.toObject(); - SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, visualItems); + SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */, visualItems); if (item->load(itemObject, itemObject["id"].toInt(), errorString)) { if (TakeoffMissionItem::isTakeoffCommand(item->mavCommand())) { // This needs to be a TakeoffMissionItem - TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, visualItems); + TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, true /* forLoad */, visualItems); takeoffItem->load(itemObject, itemObject["id"].toInt(), errorString); item->deleteLater(); item = takeoffItem; @@ -775,11 +779,11 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec QString itemType = itemObject[VisualMissionItem::jsonTypeKey].toString(); if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) { - SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, _flyView, visualItems); + SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */, visualItems); if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) { if (TakeoffMissionItem::isTakeoffCommand(static_cast(simpleItem->command()))) { // This needs to be a TakeoffMissionItem - TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, this); + TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, true /* forLoad */, this); takeoffItem->load(itemObject, nextSequenceNumber, errorString); simpleItem->deleteLater(); simpleItem = takeoffItem; @@ -919,14 +923,14 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM MissionSettingsItem* settingsItem = _addMissionSettings(visualItems); while (!stream.atEnd()) { - SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, visualItems); + SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */, visualItems); if (item->load(stream)) { if (firstItem && plannedHomePositionInFile) { settingsItem->setInitialHomePositionFromUser(item->coordinate()); } else { if (TakeoffMissionItem::isTakeoffCommand(static_cast(item->command()))) { // This needs to be a TakeoffMissionItem - TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, visualItems); + TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, true /* forLoad */, visualItems); takeoffItem->load(stream); item->deleteLater(); item = takeoffItem; @@ -2283,6 +2287,7 @@ void MissionController::setCurrentPlanViewSeqNum(int sequenceNumber, bool force) _currentPlanViewItem = nullptr; _currentPlanViewSeqNum = -1; _currentPlanViewVIIndex = -1; + _onlyInsertTakeoffValid = !_planViewSettings->takeoffItemNotRequired()->rawValue().toBool() && _visualItems->count() == 1; // First item must be takeoff _isInsertTakeoffValid = true; _isInsertLandValid = true; _isROIActive = false; @@ -2412,10 +2417,15 @@ void MissionController::setCurrentPlanViewSeqNum(int sequenceNumber, bool force) } } + // These are not valid when only takeoff is allowed + _isInsertLandValid = _isInsertLandValid && !_onlyInsertTakeoffValid; + _flyThroughCommandsAllowed = _flyThroughCommandsAllowed && !_onlyInsertTakeoffValid; + emit currentPlanViewSeqNumChanged(); emit currentPlanViewVIIndexChanged(); emit currentPlanViewItemChanged(); emit splitSegmentChanged(); + emit onlyInsertTakeoffValidChanged(); emit isInsertTakeoffValidChanged(); emit isInsertLandValidChanged(); emit isROIActiveChanged(); @@ -2513,3 +2523,9 @@ bool MissionController::isEmpty(void) const { return _visualItems->count() <= 1; } + +void MissionController::_takeoffItemNotRequiredChanged(void) +{ + // Force a recalc of allowed bits + setCurrentPlanViewSeqNum(_currentPlanViewSeqNum, true /* force */); +} diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index dc128f188a6fdad8a5a4dcf0df09da21be2e3231..2274408d6f3c9f86e38e9a09acc1a7625f5bd0c2 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -28,6 +28,7 @@ class SimpleMissionItem; class ComplexMissionItem; class MissionSettingsItem; class QDomDocument; +class PlanViewSettings; Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog) @@ -95,6 +96,7 @@ public: Q_PROPERTY(QString surveyComplexItemName READ surveyComplexItemName CONSTANT) Q_PROPERTY(QString corridorScanComplexItemName READ corridorScanComplexItemName CONSTANT) Q_PROPERTY(QString structureScanComplexItemName READ structureScanComplexItemName CONSTANT) + Q_PROPERTY(bool onlyInsertTakeoffValid MEMBER _onlyInsertTakeoffValid NOTIFY onlyInsertTakeoffValidChanged) Q_PROPERTY(bool isInsertTakeoffValid MEMBER _isInsertTakeoffValid NOTIFY isInsertTakeoffValidChanged) Q_PROPERTY(bool isInsertLandValid MEMBER _isInsertLandValid NOTIFY isInsertLandValidChanged) Q_PROPERTY(bool isROIActive MEMBER _isROIActive NOTIFY isROIActiveChanged) @@ -263,6 +265,7 @@ signals: void currentPlanViewItemChanged (void); void missionBoundingCubeChanged (void); void missionItemCountChanged (int missionItemCount); + void onlyInsertTakeoffValidChanged (void); void isInsertTakeoffValidChanged (void); void isInsertLandValidChanged (void); void isROIActiveChanged (void); @@ -286,6 +289,7 @@ private slots: void _complexBoundingBoxChanged (void); void _recalcAll (void); void _managerVehicleChanged (Vehicle* managerVehicle); + void _takeoffItemNotRequiredChanged (void); private: void _init(void); @@ -334,6 +338,7 @@ private: int _missionItemCount = 0; QmlObjectListModel* _visualItems = nullptr; MissionSettingsItem* _settingsItem = nullptr; + PlanViewSettings* _planViewSettings = nullptr; QmlObjectListModel _waypointLines; QVariantList _waypointPath; QmlObjectListModel _directionArrows; @@ -353,10 +358,11 @@ private: QGeoCoordinate _takeoffCoordinate; QGeoCoordinate _previousCoordinate; CoordinateVector* _splitSegment = nullptr; + bool _onlyInsertTakeoffValid = true; bool _isInsertTakeoffValid = true; - bool _isInsertLandValid = true; + bool _isInsertLandValid = false; bool _isROIActive = false; - bool _flyThroughCommandsAllowed = true; + bool _flyThroughCommandsAllowed = false; bool _isROIBeginCurrentItem = false; static const char* _settingsGroup; diff --git a/src/MissionManager/MissionItemTest.cc b/src/MissionManager/MissionItemTest.cc index 33946aef87e9dc3bd43a830493a9cb6cee944f4a..e2df716a21666becdf2a51b15481984dd8d41e91 100644 --- a/src/MissionManager/MissionItemTest.cc +++ b/src/MissionManager/MissionItemTest.cc @@ -278,7 +278,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 */, nullptr); + SimpleMissionItem simpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, nullptr); QString testString("10\t0\t3\t80\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n"); QTextStream testStream(&testString, QIODevice::ReadOnly); @@ -448,7 +448,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 */, nullptr); + SimpleMissionItem simpleMissionItem(_masterController, false /* flyView */, false /* forLoad */, nullptr); QString errorString; QJsonArray coordinateArray; QJsonObject jsonObject; diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index 16fd42259eb55eae535e578991a3ed1641d5fc67..b4308bdae2c143d8d1596a1ee905733220b0805b 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -52,7 +52,7 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = { { "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT }, }; -SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent) +SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, bool forLoad, QObject* parent) : VisualMissionItem (masterController, flyView, parent) , _commandTree (qgcApp()->toolbox()->missionCommandTree()) , _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32) @@ -69,13 +69,15 @@ SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, boo _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml"); _setupMetaData(); - _connectSignals(); - _updateOptionalSections(); - - _setDefaultsForCommand(); - _rebuildFacts(); - setDirty(false); + if (!forLoad) { + // We are are going to load the SimpleItem right after this then don't connnect up signalling until after load is done + _connectSignals(); + _updateOptionalSections(); + _setDefaultsForCommand(); + _rebuildFacts(); + setDirty(false); + } } SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, const MissionItem& missionItem, QObject* parent) @@ -280,7 +282,10 @@ bool SimpleMissionItem::load(QTextStream &loadStream) _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue()); _amslAltAboveTerrainFact.setRawValue(qQNaN()); } + _connectSignals(); _updateOptionalSections(); + _rebuildFacts(); + setDirty(false); } return success; @@ -313,7 +318,10 @@ bool SimpleMissionItem::load(const QJsonObject& json, int sequenceNumber, QStrin } } + _connectSignals(); _updateOptionalSections(); + _rebuildFacts(); + setDirty(false); return true; } diff --git a/src/MissionManager/SimpleMissionItem.h b/src/MissionManager/SimpleMissionItem.h index 3ca54977d9fe674c71d3466b10c95df76c6ccc7b..491e0d35b832f904872d03a8bda4f2a2f61274be 100644 --- a/src/MissionManager/SimpleMissionItem.h +++ b/src/MissionManager/SimpleMissionItem.h @@ -24,9 +24,8 @@ class SimpleMissionItem : public VisualMissionItem Q_OBJECT public: - SimpleMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent); + SimpleMissionItem(PlanMasterController* masterController, bool flyView, bool forLoad, QObject* parent); SimpleMissionItem(PlanMasterController* masterController, bool flyView, const MissionItem& missionItem, QObject* parent); - //SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent); ~SimpleMissionItem(); diff --git a/src/MissionManager/SimpleMissionItemTest.cc b/src/MissionManager/SimpleMissionItemTest.cc index caa8c5204ba045c3353e5ded11ba2583c25fd7ac..44aa0b509f9564eeb904598b44f58c9492103779 100644 --- a/src/MissionManager/SimpleMissionItemTest.cc +++ b/src/MissionManager/SimpleMissionItemTest.cc @@ -166,7 +166,7 @@ void SimpleMissionItemTest::_testEditorFacts(void) void SimpleMissionItemTest::_testDefaultValues(void) { - SimpleMissionItem item(_masterController, false /* flyView */, nullptr); + SimpleMissionItem item(_masterController, false /* flyView */, false /* forLoad */, nullptr); item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT); item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT); diff --git a/src/MissionManager/SurveyComplexItem.cc b/src/MissionManager/SurveyComplexItem.cc index 79510f5a1fe6d241d4cc1db6e3651c76a4a25d7e..3ee340f136baa4ec2632d2d2ce1481ced72f3946 100644 --- a/src/MissionManager/SurveyComplexItem.cc +++ b/src/MissionManager/SurveyComplexItem.cc @@ -79,6 +79,11 @@ SurveyComplexItem::SurveyComplexItem(PlanMasterController* masterController, boo _turnAroundDistanceFact.setRawValue(10); } + if (_controllerVehicle && !(_controllerVehicle->fixedWing() || _controllerVehicle->vtol())) { + // Only fixed wing flight paths support alternate transects + _flyAlternateTransectsFact.setRawValue(false); + } + // We override the altitude to the mission default if (_cameraCalc.isManualCamera() || !_cameraCalc.valueSetIsDistance()->rawValue().toBool()) { _cameraCalc.distanceToSurface()->setRawValue(qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue()); diff --git a/src/MissionManager/TakeoffMissionItem.cc b/src/MissionManager/TakeoffMissionItem.cc index 08400bf9e17852df3289b7d72f4f114fec2bae9a..335f1b3a474c8d9189da668ba1a08dc5cc27a42e 100644 --- a/src/MissionManager/TakeoffMissionItem.cc +++ b/src/MissionManager/TakeoffMissionItem.cc @@ -20,26 +20,27 @@ #include "SettingsManager.h" #include "PlanMasterController.h" -TakeoffMissionItem::TakeoffMissionItem(PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent) - : SimpleMissionItem (masterController, flyView, parent) +TakeoffMissionItem::TakeoffMissionItem(PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, bool forLoad, QObject* parent) + : SimpleMissionItem (masterController, flyView, forLoad, parent) , _settingsItem (settingsItem) { - _init(); + _init(forLoad); } TakeoffMissionItem::TakeoffMissionItem(MAV_CMD takeoffCmd, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent) - : SimpleMissionItem (masterController, flyView, parent) + : SimpleMissionItem (masterController, flyView, false /* forLoad */, parent) , _settingsItem (settingsItem) { setCommand(takeoffCmd); - _init(); + _init(false /* forLoad */); } TakeoffMissionItem::TakeoffMissionItem(const MissionItem& missionItem, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent) : SimpleMissionItem (masterController, flyView, missionItem, parent) , _settingsItem (settingsItem) { - _init(); + _init(false /* forLoad */); + _wizardMode = false; } TakeoffMissionItem::~TakeoffMissionItem() @@ -47,7 +48,7 @@ TakeoffMissionItem::~TakeoffMissionItem() } -void TakeoffMissionItem::_init(void) +void TakeoffMissionItem::_init(bool forLoad) { _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml"); @@ -69,10 +70,15 @@ void TakeoffMissionItem::_init(void) } } + if (forLoad) { + // Load routines will set the rest up after load + return; + } + _initLaunchTakeoffAtSameLocation(); if (homePosition.isValid() && coordinate().isValid()) { - // Item already full specified, most likely from mission load from storage + // Item already fully specified, most likely from mission load from storage _wizardMode = false; } else { if (_launchTakeoffAtSameLocation && homePosition.isValid()) { @@ -140,6 +146,7 @@ bool TakeoffMissionItem::load(QTextStream &loadStream) if (success) { _initLaunchTakeoffAtSameLocation(); } + _wizardMode = false; // Always be off for loaded items return success; } @@ -149,6 +156,7 @@ bool TakeoffMissionItem::load(const QJsonObject& json, int sequenceNumber, QStri if (success) { _initLaunchTakeoffAtSameLocation(); } + _wizardMode = false; // Always be off for loaded items return success; } diff --git a/src/MissionManager/TakeoffMissionItem.h b/src/MissionManager/TakeoffMissionItem.h index 13a1cb65440c13f55a7fc397b9c033567393c69d..6a1114fcd66d9a3002d521b7e30fb8d66422e1fd 100644 --- a/src/MissionManager/TakeoffMissionItem.h +++ b/src/MissionManager/TakeoffMissionItem.h @@ -21,7 +21,7 @@ class TakeoffMissionItem : public SimpleMissionItem Q_OBJECT public: - TakeoffMissionItem(PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent); + 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); @@ -57,7 +57,7 @@ signals: void launchTakeoffAtSameLocationChanged (bool launchTakeoffAtSameLocation); private: - void _init(void); + void _init(bool forLoad); void _initLaunchTakeoffAtSameLocation(void); MissionSettingsItem* _settingsItem; diff --git a/src/MissionManager/TransectStyleComplexItem.cc b/src/MissionManager/TransectStyleComplexItem.cc index 4fbe9a3dd16df76255a9ae476ad2997f291847d6..89c0a768e5bb3eb8df76334936f79ed231a9cb4a 100644 --- a/src/MissionManager/TransectStyleComplexItem.cc +++ b/src/MissionManager/TransectStyleComplexItem.cc @@ -498,7 +498,19 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QListappSettings()->offlineEditingHoverSpeed()->rawValue().toDouble()) , _mavlinkProtocolRequestComplete(true) , _maxProtoVersion(200) - , _vehicleCapabilitiesKnown(true) + , _capabilityBitsKnown(true) , _capabilityBits(MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY) , _highLatencyLink(false) , _receivingAttitudeQuaternion(false) @@ -712,6 +706,34 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes return; } + if (!_capabilityBitsKnown && message.msgid == MAVLINK_MSG_ID_HEARTBEAT && message.compid == MAV_COMP_ID_AUTOPILOT1) { + // We want to try to get capabilities as fast as possible so we retry on heartbeats + bool foundRequest = false; + for (MavCommandQueueEntry_t& queuedCommand : _mavCommandQueue) { + if (queuedCommand.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) { + foundRequest = true; + break; + } + } + if (!foundRequest) { + _capabilitiesRetryCount++; + if (_capabilitiesRetryCount == 1) { + _capabilitiesRetryElapsed.start(); + } else if (_capabilitiesRetryElapsed.elapsed() > 10000){ + qCDebug(VehicleLog) << "Giving up on getting AUTOPILOT_VERSION after 10 seconds"; + qgcApp()->showMessage(QStringLiteral("Vehicle failed to send AUTOPILOT_VERSION after waiting/retrying for 10 seconds")); + _handleUnsupportedRequestAutopilotCapabilities(); + } else { + // Vehicle never sent us AUTOPILOT_VERSION response. Try again. + qCDebug(VehicleLog) << QStringLiteral("Sending MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES again due to no response with AUTOPILOT_VERSION - _capabilitiesRetryCount(%1) elapsed(%2)").arg(_capabilitiesRetryCount).arg(_capabilitiesRetryElapsed.elapsed()); + sendMavCommand(MAV_COMP_ID_ALL, + MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES, + true, // Show error on failure + 1); // Request firmware version + } + } + } + switch (message.msgid) { case MAVLINK_MSG_ID_HOME_POSITION: _handleHomePosition(message); @@ -1308,7 +1330,7 @@ void Vehicle::_handleAltitude(mavlink_message_t& message) void Vehicle::_setCapabilities(uint64_t capabilityBits) { _capabilityBits = capabilityBits; - _vehicleCapabilitiesKnown = true; + _capabilityBitsKnown = true; emit capabilitiesKnownChanged(true); emit capabilityBitsChanged(_capabilityBits); @@ -1321,6 +1343,8 @@ void Vehicle::_setCapabilities(uint64_t capabilityBits) qCDebug(VehicleLog) << QString("Vehicle %1 GeoFence").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE ? supports : doesNotSupport); qCDebug(VehicleLog) << QString("Vehicle %1 RallyPoints").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY ? supports : doesNotSupport); qCDebug(VehicleLog) << QString("Vehicle %1 Terrain").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_TERRAIN ? supports : doesNotSupport); + + _setMaxProtoVersionFromBothSources(); } void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& message) @@ -1383,8 +1407,9 @@ void Vehicle::_handleProtocolVersion(LinkInterface *link, mavlink_message_t& mes qCDebug(VehicleLog) << "_handleProtocolVersion" << protoVersion.max_version; + _mavlinkProtocolRequestMaxProtoVersion = protoVersion.max_version; _mavlinkProtocolRequestComplete = true; - _setMaxProtoVersion(protoVersion.max_version); + _setMaxProtoVersionFromBothSources(); _startPlanRequest(); } @@ -1398,6 +1423,19 @@ void Vehicle::_setMaxProtoVersion(unsigned version) { } } +void Vehicle::_setMaxProtoVersionFromBothSources() +{ + if (_mavlinkProtocolRequestComplete && _capabilityBitsKnown) { + if (_mavlinkProtocolRequestMaxProtoVersion != 0) { + qCDebug(VehicleLog) << "_setMaxProtoVersionFromBothSources using protocol version message"; + _setMaxProtoVersion(_mavlinkProtocolRequestMaxProtoVersion); + } else { + qCDebug(VehicleLog) << "_setMaxProtoVersionFromBothSources using capability bits"; + _setMaxProtoVersion(capabilityBits() & MAV_PROTOCOL_CAPABILITY_MAVLINK2 ? 200 : 100); + } + } +} + QString Vehicle::vehicleUIDStr() { QString uid; @@ -2621,7 +2659,7 @@ void Vehicle::_startPlanRequest() // - Parameter download is complete // - We know the vehicle capabilities // - We know the max mavlink protocol version - if (_parameterManager->parametersReady() && _vehicleCapabilitiesKnown && _mavlinkProtocolRequestComplete) { + if (_parameterManager->parametersReady() && _capabilityBitsKnown && _mavlinkProtocolRequestComplete) { qCDebug(VehicleLog) << "_startPlanRequest"; _missionManagerInitialRequestSent = true; if (_settingsManager->appSettings()->autoLoadMissions()->rawValue().toBool()) { @@ -2640,7 +2678,7 @@ void Vehicle::_startPlanRequest() } else { if (!_parameterManager->parametersReady()) { qCDebug(VehicleLog) << "Delaying _startPlanRequest due to parameters not ready"; - } else if (!_vehicleCapabilitiesKnown) { + } else if (!_capabilityBitsKnown) { qCDebug(VehicleLog) << "Delaying _startPlanRequest due to vehicle capabilities not known"; } else if (!_mavlinkProtocolRequestComplete) { qCDebug(VehicleLog) << "Delaying _startPlanRequest due to mavlink protocol request not complete"; @@ -3405,19 +3443,9 @@ void Vehicle::_handleUnsupportedRequestProtocolVersion() // We end up here if either the vehicle does not support the MAV_CMD_REQUEST_PROTOCOL_VERSION command or if // we never received an Ack back for the command. - // If the link isn't already running Mavlink V2 fall back to the capability bits to determine whether to use Mavlink V2 or not. - if (_maxProtoVersion == 0) { - if (capabilitiesKnown()) { - unsigned vehicleMaxProtoVersion = capabilityBits() & MAV_PROTOCOL_CAPABILITY_MAVLINK2 ? 200 : 100; - qCDebug(VehicleLog) << QStringLiteral("Setting _maxProtoVersion to %1 based on capabilitity bits since not yet set.").arg(vehicleMaxProtoVersion); - _setMaxProtoVersion(vehicleMaxProtoVersion); - } else { - qCDebug(VehicleLog) << "Waiting for capabilities to be known to set _maxProtoVersion"; - } - } else { - qCDebug(VehicleLog) << "Leaving _maxProtoVersion at current value" << _maxProtoVersion; - } + // _mavlinkProtocolRequestMaxProtoVersion stays at 0 to indicate unknown _mavlinkProtocolRequestComplete = true; + _setMaxProtoVersionFromBothSources(); // Determining protocol version is one of the triggers to possibly start downloading the plan _startPlanRequest(); @@ -3428,8 +3456,9 @@ void Vehicle::_protocolVersionTimeOut() // The PROTOCOL_VERSION message didn't make it through the pipe from Vehicle->QGC. // This means although the vehicle may support mavlink 2, the pipe does not. qCDebug(VehicleLog) << QStringLiteral("Setting _maxProtoVersion to 100 due to timeout on receiving PROTOCOL_VERSION message."); - _setMaxProtoVersion(100); + _mavlinkProtocolRequestMaxProtoVersion = 100; _mavlinkProtocolRequestComplete = true; + _setMaxProtoVersionFromBothSources(); _startPlanRequest(); } diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index e4f9191da5a8e61ce831fdab7747f30717c8bd3a..eb0d39b8f4f44922e75ce4c3a92b9614f465ebdb 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -12,6 +12,7 @@ #include #include #include +#include #include "FactGroup.h" #include "LinkInterface.h" @@ -1082,7 +1083,7 @@ public: const QVariantList& toolBarIndicators (); const QVariantList& staticCameraList () const; - bool capabilitiesKnown () const { return _vehicleCapabilitiesKnown; } + bool capabilitiesKnown () const { return _capabilityBitsKnown; } uint64_t capabilityBits () const { return _capabilityBits; } // Change signalled by capabilityBitsChanged QGCCameraManager* dynamicCameras () { return _cameras; } @@ -1100,7 +1101,8 @@ public: void _setFlying(bool flying); void _setLanding(bool landing); void _setHomePosition(QGeoCoordinate& homeCoord); - void _setMaxProtoVersion (unsigned version); + void _setMaxProtoVersion(unsigned version); + void _setMaxProtoVersionFromBothSources(); /// Vehicle is about to be deleted void prepareDelete(); @@ -1410,9 +1412,10 @@ private: uint32_t _telemetryTXBuffer; int _telemetryLNoise; int _telemetryRNoise; - bool _mavlinkProtocolRequestComplete; - unsigned _maxProtoVersion; - bool _vehicleCapabilitiesKnown; + bool _mavlinkProtocolRequestComplete = false; + unsigned _mavlinkProtocolRequestMaxProtoVersion = 0; + unsigned _maxProtoVersion = 0; + bool _capabilityBitsKnown = false; uint64_t _capabilityBits; bool _highLatencyLink; bool _receivingAttitudeQuaternion; @@ -1432,8 +1435,10 @@ private: QList _mavCommandQueue; QTimer _mavCommandAckTimer; int _mavCommandRetryCount; - static const int _mavCommandMaxRetryCount = 3; - static const int _mavCommandAckTimeoutMSecs = 3000; + int _capabilitiesRetryCount = 0; + QTime _capabilitiesRetryElapsed; + static const int _mavCommandMaxRetryCount = 3; + static const int _mavCommandAckTimeoutMSecs = 3000; static const int _mavCommandAckTimeoutMSecsHighLatency = 120000; QString _prearmError; diff --git a/src/VehicleSetup/FirmwareUpgrade.qml b/src/VehicleSetup/FirmwareUpgrade.qml index 178380924e179f71471dc129b4a4d998399b3a23..094b30b2fb39060ff6d8fa8f6d720bee69342745 100644 --- a/src/VehicleSetup/FirmwareUpgrade.qml +++ b/src/VehicleSetup/FirmwareUpgrade.qml @@ -383,8 +383,7 @@ SetupPage { anchors.right: parent.right visible: !px4Flow && apmFlightStack.checked && !controller.downloadingFirmwareList && controller.apmFirmwareNames.length !== 0 model: controller.apmFirmwareNames - - onModelChanged: console.log("model", model) + onModelChanged: currentIndex = controller.apmFirmwareNamesBestIndex } QGCLabel { diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/VehicleSetup/FirmwareUpgradeController.cc index ae5ec5d012b428f06f4ff4bbad76e4399c67a5b0..e04fad68cb43ef7b6a185322eb1383d5291136cb 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.cc +++ b/src/VehicleSetup/FirmwareUpgradeController.cc @@ -730,52 +730,47 @@ void FirmwareUpgradeController::_buildAPMFirmwareNames(void) QString boardDescription = _foundBoardInfo.description(); quint16 boardVID = _foundBoardInfo.vendorIdentifier(); quint16 boardPID = _foundBoardInfo.productIdentifier(); - -#if 0 - // This is left in for debugging manifest problems - boardDescription = "KakuteF7"; - boardVID = 1155; - boardPID = 22336; -#endif + uint32_t rawBoardId = _bootloaderBoardID == Bootloader::boardIDPX4FMUV3 ? Bootloader::boardIDPX4FMUV2 : _bootloaderBoardID; qCDebug(FirmwareUpgradeLog) << QStringLiteral("_buildAPMFirmwareNames description(%1) vid(%2/0x%3) pid(%4/0x%5)").arg(boardDescription).arg(boardVID).arg(boardVID, 1, 16).arg(boardPID).arg(boardPID, 1, 16); _apmFirmwareNames.clear(); + _apmFirmwareNamesBestIndex = -1; _apmFirmwareUrls.clear(); QString apmDescriptionSuffix("-BL"); + QString boardDescriptionPrefix; bool bootloaderMatch = boardDescription.endsWith(apmDescriptionSuffix); + int currentIndex = 0; for (const ManifestFirmwareInfo_t& firmwareInfo: _rgManifestFirmwareInfo) { bool match = false; - if (firmwareInfo.firmwareBuildType == _selectedFirmwareBuildType && firmwareInfo.chibios == chibios && firmwareInfo.vehicleType == vehicleType) { - if (bootloaderMatch) { - if (firmwareInfo.rgBootloaderPortString.contains(boardDescription)) { - qCDebug(FirmwareUpgradeLog) << "Bootloader match:" << firmwareInfo.friendlyName << boardDescription << firmwareInfo.rgBootloaderPortString << firmwareInfo.url << firmwareInfo.vehicleType; - match = true; - } + if (firmwareInfo.firmwareBuildType == _selectedFirmwareBuildType && firmwareInfo.chibios == chibios && firmwareInfo.vehicleType == vehicleType && firmwareInfo.boardId == rawBoardId) { + if (firmwareInfo.fmuv2 && _bootloaderBoardID == Bootloader::boardIDPX4FMUV3) { + qCDebug(FirmwareUpgradeLog) << "Skipping fmuv2 manifest entry for fmuv3 board:" << firmwareInfo.friendlyName << boardDescription << firmwareInfo.rgBootloaderPortString << firmwareInfo.url << firmwareInfo.vehicleType; } else { - if (firmwareInfo.rgVID.contains(boardVID) && firmwareInfo.rgPID.contains(boardPID)) { - qCDebug(FirmwareUpgradeLog) << "VID/PID match:" << firmwareInfo.friendlyName << boardVID << boardPID << _bootloaderBoardID << firmwareInfo.url << firmwareInfo.vehicleType; - match = true; + qCDebug(FirmwareUpgradeLog) << "Board id match:" << firmwareInfo.friendlyName << boardDescription << firmwareInfo.rgBootloaderPortString << firmwareInfo.url << firmwareInfo.vehicleType; + match = true; + if (bootloaderMatch && _apmFirmwareNamesBestIndex == -1 && firmwareInfo.rgBootloaderPortString.contains(boardDescription)) { + _apmFirmwareNamesBestIndex = currentIndex; + qCDebug(FirmwareUpgradeLog) << "Bootloader best match:" << firmwareInfo.friendlyName << boardDescription << firmwareInfo.rgBootloaderPortString << firmwareInfo.url << firmwareInfo.vehicleType; } } } - // Do a final filter on fmuv2/fmuv3 - if (match && _bootloaderBoardID == Bootloader::boardIDPX4FMUV3) { - match = !firmwareInfo.fmuv2; - } - if (match) { _apmFirmwareNames.append(firmwareInfo.friendlyName); _apmFirmwareUrls.append(firmwareInfo.url); + currentIndex++; } } - if (_apmFirmwareNames.count() > 1) { - _apmFirmwareNames.prepend(tr("Choose board type")); - _apmFirmwareUrls.prepend(QString()); + if (_apmFirmwareNamesBestIndex == -1) { + _apmFirmwareNamesBestIndex++; + if (_apmFirmwareNames.count() > 1) { + _apmFirmwareNames.prepend(tr("Choose board type")); + _apmFirmwareUrls.prepend(QString()); + } } emit apmFirmwareNamesChanged(); diff --git a/src/VehicleSetup/FirmwareUpgradeController.h b/src/VehicleSetup/FirmwareUpgradeController.h index 5a375a9ae4a8b10bfd1374863a9009638bab64dc..88f20f00af6b25dfa6c76167da346d7a2e396c91 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.h +++ b/src/VehicleSetup/FirmwareUpgradeController.h @@ -94,6 +94,7 @@ public: Q_PROPERTY(bool px4FlowBoard READ px4FlowBoard NOTIFY boardFound) Q_PROPERTY(FirmwareBuildType_t selectedFirmwareBuildType READ selectedFirmwareBuildType WRITE setSelectedFirmwareBuildType NOTIFY selectedFirmwareBuildTypeChanged) Q_PROPERTY(QStringList apmFirmwareNames MEMBER _apmFirmwareNames NOTIFY apmFirmwareNamesChanged) + Q_PROPERTY(int apmFirmwareNamesBestIndex MEMBER _apmFirmwareNamesBestIndex NOTIFY apmFirmwareNamesChanged) Q_PROPERTY(QStringList apmFirmwareUrls MEMBER _apmFirmwareUrls NOTIFY apmFirmwareNamesChanged) Q_PROPERTY(QString px4StableVersion READ px4StableVersion NOTIFY px4StableVersionChanged) Q_PROPERTY(QString px4BetaVersion READ px4BetaVersion NOTIFY px4BetaVersionChanged) @@ -308,6 +309,7 @@ private: QMap _manifestMavFirmwareVersionTypeToFirmwareBuildTypeMap; QMap _manifestMavTypeToFirmwareVehicleTypeMap; QStringList _apmFirmwareNames; + int _apmFirmwareNamesBestIndex = 0; QStringList _apmFirmwareUrls; Fact* _apmChibiOSSetting; Fact* _apmVehicleTypeSetting; diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index c698d44af44b1e811df4f994d099107984a3fab8..865e4fa19f11c4c5a526e672dbdb767fcd09087d 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -43,6 +43,7 @@ Rectangle { property Fact _followTarget: QGroundControl.settingsManager.appSettings.followTarget property real _panelWidth: _root.width * _internalWidthRatio property real _margins: ScreenTools.defaultFontPixelWidth + property var _planViewSettings: QGroundControl.settingsManager.planViewSettings property string _videoSource: QGroundControl.settingsManager.videoSettings.videoSource.value property bool _isGst: QGroundControl.videoManager.isGStreamer @@ -595,7 +596,7 @@ Rectangle { QGCLabel { id: planViewSectionLabel text: qsTr("Plan View") - visible: QGroundControl.settingsManager.planViewSettings.visible + visible: _planViewSettings.visible } Rectangle { Layout.preferredHeight: planViewCol.height + (_margins * 2) @@ -626,6 +627,12 @@ Rectangle { text: qsTr("Use MAV_CMD_CONDITION_GATE for pattern generation") fact: QGroundControl.settingsManager.planViewSettings.useConditionGate } + + FactCheckBox { + text: qsTr("Missions Do Not Require Takeoff Item") + fact: _planViewSettings.takeoffItemNotRequired + visible: _planViewSettings.takeoffItemNotRequired.visible + } } } @@ -888,16 +895,27 @@ Rectangle { visible: QGroundControl.settingsManager.adsbVehicleManagerSettings.visible } Rectangle { - Layout.preferredHeight: adsbGrid.height + (_margins * 2) + Layout.preferredHeight: adsbGrid.y + adsbGrid.height + _margins Layout.preferredWidth: adsbGrid.width + (_margins * 2) color: qgcPal.windowShade visible: adsbSectionLabel.visible Layout.fillWidth: true + QGCLabel { + id: warningLabel + anchors.margins: _margins + anchors.top: parent.top + anchors.left: parent.left + anchors.right: parent.right + font.pointSize: ScreenTools.smallFontPointSize + wrapMode: Text.WordWrap + text: qsTr("Note: These setting are not meant for use with an ADSB transponder which is situated on the vehicle.") + } + GridLayout { id: adsbGrid anchors.topMargin: _margins - anchors.top: parent.top + anchors.top: warningLabel.bottom Layout.fillWidth: true anchors.horizontalCenter: parent.horizontalCenter columns: 2 diff --git a/src/ui/toolbar/MainToolBar.qml b/src/ui/toolbar/MainToolBar.qml index 2e6eaf1167aa074236d42eaa3dc568164bd8d9f8..fb6dd695fe1fc25a7caa701d094061a9351d42da 100644 --- a/src/ui/toolbar/MainToolBar.qml +++ b/src/ui/toolbar/MainToolBar.qml @@ -42,7 +42,8 @@ Item { Connections { target: setupWindow onVisibleChanged: { - if(setupWindow.visible) { + if (setupWindow.visible) { + buttonRow.clearAllChecks() setupButton.checked = true } }