From cc1fa95942fdc31a8445275b75ec88b19dba0b88 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Mon, 14 Aug 2017 12:44:05 -0700 Subject: [PATCH 01/12] Add debuggable to manifest --- android/AndroidManifest.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/android/AndroidManifest.xml b/android/AndroidManifest.xml index b95c5ae..7c0efd0 100644 --- a/android/AndroidManifest.xml +++ b/android/AndroidManifest.xml @@ -1,6 +1,6 @@ - + From ae5b704d94dd6845b350891bca6a2ba201d65e24 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Thu, 17 Aug 2017 10:27:15 -0700 Subject: [PATCH 02/12] Remove extra plugin --- src/QtLocationPlugin/QMLControl/OfflineMap.qml | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/QtLocationPlugin/QMLControl/OfflineMap.qml b/src/QtLocationPlugin/QMLControl/OfflineMap.qml index 2c7b04c..aa262b0 100644 --- a/src/QtLocationPlugin/QMLControl/OfflineMap.qml +++ b/src/QtLocationPlugin/QMLControl/OfflineMap.qml @@ -342,8 +342,6 @@ QGCView { property bool isSatelliteMap: activeMapType.name.indexOf("Satellite") > -1 || activeMapType.name.indexOf("Hybrid") > -1 - plugin: Plugin { name: "QGroundControl" } - MapRectangle { id: mapBoundary border.width: 2 From 16657ae439a7c7872fc4c64a8508eb3c09d51e73 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Thu, 17 Aug 2017 10:27:43 -0700 Subject: [PATCH 03/12] Add missing settings to Manual grid --- src/PlanView/SurveyItemEditor.qml | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/src/PlanView/SurveyItemEditor.qml b/src/PlanView/SurveyItemEditor.qml index 5f68e3d..9f417ff 100644 --- a/src/PlanView/SurveyItemEditor.qml +++ b/src/PlanView/SurveyItemEditor.qml @@ -584,6 +584,24 @@ Rectangle { Layout.fillWidth: true } + FactCheckBox { + text: qsTr("Hover and capture image") + fact: missionItem.hoverAndCapture + visible: missionItem.hoverAndCaptureAllowed + Layout.columnSpan: 2 + onClicked: { + if (checked) { + missionItem.cameraTriggerInTurnaround.rawValue = false + } + } + } + + FactCheckBox { + text: qsTr("Take images in turnarounds") + fact: missionItem.cameraTriggerInTurnaround + enabled: !missionItem.hoverAndCapture.rawValue + Layout.columnSpan: 2 + } QGCCheckBox { text: qsTr("Refly at 90 degree offset") From fc25bd3ebd86c567f17f89b63fd658246dccc5f3 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Thu, 17 Aug 2017 10:27:53 -0700 Subject: [PATCH 04/12] Fix camera shot calculation --- src/MissionManager/SurveyMissionItem.cc | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/MissionManager/SurveyMissionItem.cc b/src/MissionManager/SurveyMissionItem.cc index eb28e7e..94520ee 100644 --- a/src/MissionManager/SurveyMissionItem.cc +++ b/src/MissionManager/SurveyMissionItem.cc @@ -747,7 +747,9 @@ void SurveyMissionItem::_generateGrid(void) _setSurveyDistance(surveyDistance); if (cameraShots == 0 && _triggerCamera()) { - cameraShots = (int)ceil(surveyDistance / _triggerDistance()); + cameraShots = (int)floor(surveyDistance / _triggerDistance()); + // Take into account immediate camera trigger at waypoint entry + cameraShots++; } _setCameraShots(cameraShots); @@ -1065,7 +1067,9 @@ int SurveyMissionItem::_gridGenerator(const QList& polygonPoints, QLis // Calc camera shots here if there are no images in turnaround if (_triggerCamera() && !_imagesEverywhere()) { for (int i=0; i Date: Fri, 18 Aug 2017 13:27:04 -0700 Subject: [PATCH 05/12] Stop noisy logging --- src/FlightDisplay/GuidedActionsController.qml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/FlightDisplay/GuidedActionsController.qml b/src/FlightDisplay/GuidedActionsController.qml index 4970fda..33604e7 100644 --- a/src/FlightDisplay/GuidedActionsController.qml +++ b/src/FlightDisplay/GuidedActionsController.qml @@ -125,6 +125,8 @@ Item { property bool __pauseVehicleSupported: _activeVehicle ? _activeVehicle.pauseVehicleSupported : false property bool __flightMode: _flightMode + /* + Leaving this code in for use while debugging function _outputState() { console.log(qsTr("_activeVehicle(%1) _vehicleArmed(%2) guidedModeSupported(%3) _vehicleFlying(%4) _vehicleInRTLMode(%5) pauseVehicleSupported(%6) _vehiclePaused(%7) _flightMode(%8)").arg(_activeVehicle ? 1 : 0).arg(_vehicleArmed ? 1 : 0).arg(__guidedModeSupported ? 1 : 0).arg(_vehicleFlying ? 1 : 0).arg(_vehicleInRTLMode ? 1 : 0).arg(__pauseVehicleSupported ? 1 : 0).arg(_vehiclePaused ? 1 : 0).arg(_flightMode)) } @@ -139,16 +141,16 @@ Item { on__PauseVehicleSupportedChanged: _outputState() // End of hack + */ on_VehicleFlyingChanged: { - _outputState() + //_outputState() if (!_vehicleFlying) { // We use _vehicleWasFLying to help trigger Resume Mission only if the vehicle actually flew and came back down. // Otherwise it may trigger during the Start Mission sequence due to signal ordering or armed and resume mission index. _vehicleWasFlying = true } } - property var _actionData on_CurrentMissionIndexChanged: console.log("_currentMissionIndex", _currentMissionIndex) From a476cf58d9631b7a6dc203ede80de08b6b6f94b7 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Fri, 18 Aug 2017 13:27:57 -0700 Subject: [PATCH 06/12] Fix resume mission generation and crashes * Resume index adjust to previous coordinate command * Takeoff always added to resume mission * Remove camera id checks which are no longer part of spec * Simplified de-dup logic --- src/MissionManager/MissionManager.cc | 122 +++++++++++++++-------------------- 1 file changed, 51 insertions(+), 71 deletions(-) diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index 5b3372f..f027f2d 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -988,7 +988,23 @@ void MissionManager::generateResumeMission(int resumeIndex) } } - resumeIndex = qMin(resumeIndex, _missionItems.count() - 1); + // Be anal about crap input + resumeIndex = qMax(0, qMin(resumeIndex, _missionItems.count() - 1)); + + // Adjust resume index to be a location based command + const MissionCommandUIInfo* uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, _missionItems[resumeIndex]->command()); + if (!uiInfo || uiInfo->isStandaloneCoordinate() || !uiInfo->specifiesCoordinate()) { + // We have to back up to the last command which the vehicle flies through + while (--resumeIndex > 0) { + uiInfo = qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_vehicle, _missionItems[resumeIndex]->command()); + if (uiInfo && (uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate())) { + // Found it + break; + } + + } + } + resumeIndex = qMax(0, resumeIndex); int seqNum = 0; QList resumeMission; @@ -1008,20 +1024,19 @@ void MissionManager::generateResumeMission(int resumeIndex) << MAV_CMD_IMAGE_STOP_CAPTURE << MAV_CMD_VIDEO_START_CAPTURE << MAV_CMD_VIDEO_STOP_CAPTURE - << MAV_CMD_DO_CHANGE_SPEED; - if (_vehicle->fixedWing() && _vehicle->px4Firmware()) { - includedResumeCommands << MAV_CMD_NAV_TAKEOFF; - } + << MAV_CMD_DO_CHANGE_SPEED + << MAV_CMD_SET_CAMERA_MODE + << MAV_CMD_NAV_TAKEOFF; bool addHomePosition = _vehicle->firmwarePlugin()->sendHomePositionToVehicle(); int setCurrentIndex = addHomePosition ? 1 : 0; - int resumeCommandCount = 0; + int prefixCommandCount = 0; for (int i=0; i<_missionItems.count(); i++) { MissionItem* oldItem = _missionItems[i]; if ((i == 0 && addHomePosition) || i >= resumeIndex || includedResumeCommands.contains(oldItem->command())) { if (i < resumeIndex) { - resumeCommandCount++; + prefixCommandCount++; } MissionItem* newItem = new MissionItem(*oldItem, this); newItem->setIsCurrentItem( i == setCurrentIndex); @@ -1029,91 +1044,56 @@ void MissionManager::generateResumeMission(int resumeIndex) resumeMission.append(newItem); } } + prefixCommandCount = qMax(0, qMin(prefixCommandCount, resumeMission.count())); // Anal prevention against crashes // De-dup and remove no-ops from the commands which were added to the front of the mission bool foundROI = false; - bool foundCamTrigDist = false; - QList imageStartCameraIds; - QList imageStopCameraIds; - QList videoStartCameraIds; - QList videoStopCameraIds; - while (resumeIndex >= 0) { - MissionItem* resumeItem = resumeMission[resumeIndex]; + bool foundCameraSetMode = false; + bool foundCameraStartStop = false; + prefixCommandCount--; // Change from count to array index + while (prefixCommandCount >= 0) { + MissionItem* resumeItem = resumeMission[prefixCommandCount]; switch (resumeItem->command()) { + case MAV_CMD_SET_CAMERA_MODE: + // Only keep the last one + if (foundCameraSetMode) { + resumeMission.removeAt(prefixCommandCount); + } + foundCameraSetMode = true; + break; case MAV_CMD_DO_SET_ROI: // Only keep the last one if (foundROI) { - resumeMission.removeAt(resumeIndex); + resumeMission.removeAt(prefixCommandCount); } foundROI = true; break; case MAV_CMD_DO_SET_CAM_TRIGG_DIST: - // Only keep the last one - if (foundCamTrigDist) { - resumeMission.removeAt(resumeIndex); - } - foundCamTrigDist = true; - break; - case MAV_CMD_IMAGE_START_CAPTURE: - { - // FIXME: Handle single image capture - int cameraId = resumeItem->param1(); - - if (resumeItem->param3() == 1) { - // This is an individual image capture command, remove it - resumeMission.removeAt(resumeIndex); - break; - } - // If we already found an image stop, then all image start/stop commands are useless - // De-dup repeated image start commands - // Otherwise keep only the last image start - if (imageStopCameraIds.contains(cameraId) || imageStartCameraIds.contains(cameraId)) { - resumeMission.removeAt(resumeIndex); - } - if (!imageStopCameraIds.contains(cameraId)) { - imageStopCameraIds.append(cameraId); - } - } - break; case MAV_CMD_IMAGE_STOP_CAPTURE: - { - int cameraId = resumeItem->param1(); - // Image stop only matters to kill all previous image starts - if (!imageStopCameraIds.contains(cameraId)) { - imageStopCameraIds.append(cameraId); - } - resumeMission.removeAt(resumeIndex); - } - break; case MAV_CMD_VIDEO_START_CAPTURE: - { - int cameraId = resumeItem->param1(); - // If we've already found a video stop, then all video start/stop commands are useless - // De-dup repeated video start commands - // Otherwise keep only the last video start - if (videoStopCameraIds.contains(cameraId) || videoStopCameraIds.contains(cameraId)) { - resumeMission.removeAt(resumeIndex); - } - if (!videoStopCameraIds.contains(cameraId)) { - videoStopCameraIds.append(cameraId); + case MAV_CMD_VIDEO_STOP_CAPTURE: + // Only keep the first of these commands that are found + if (foundCameraStartStop) { + resumeMission.removeAt(prefixCommandCount); } - } + foundCameraStartStop = true; break; - case MAV_CMD_VIDEO_STOP_CAPTURE: - { - int cameraId = resumeItem->param1(); - // Video stop only matters to kill all previous video starts - if (!videoStopCameraIds.contains(cameraId)) { - videoStopCameraIds.append(cameraId); + case MAV_CMD_IMAGE_START_CAPTURE: + // Only keep the first of these commands that are found + if (foundCameraStartStop) { + resumeMission.removeAt(prefixCommandCount); } - resumeMission.removeAt(resumeIndex); - } + if (resumeItem->param3() != 0) { + // Remove commands which do no trigger by time + resumeMission.removeAt(prefixCommandCount); + } + foundCameraStartStop = true; break; default: break; } - resumeIndex--; + prefixCommandCount--; } // Send to vehicle From bfe6d6099896a9559ea7ee5df00b1489a58e947c Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Sat, 19 Aug 2017 13:04:42 -0700 Subject: [PATCH 07/12] Fix flight speed signaling to update further mission items --- src/MissionManager/CameraSection.cc | 1 + src/MissionManager/CameraSection.h | 1 + src/MissionManager/MissionSettingsItem.cc | 2 +- src/MissionManager/SimpleMissionItem.cc | 8 +++----- src/MissionManager/SpeedSection.cc | 19 +++++++++++++++++-- src/MissionManager/SpeedSection.h | 10 ++++++++-- 6 files changed, 31 insertions(+), 10 deletions(-) diff --git a/src/MissionManager/CameraSection.cc b/src/MissionManager/CameraSection.cc index 4ff082d..12b3875 100644 --- a/src/MissionManager/CameraSection.cc +++ b/src/MissionManager/CameraSection.cc @@ -67,6 +67,7 @@ CameraSection::CameraSection(Vehicle* vehicle, QObject* parent) connect(this, &CameraSection::specifyGimbalChanged, this, &CameraSection::_setDirty); connect(this, &CameraSection::specifyCameraModeChanged, this, &CameraSection::_setDirty); + connect(this, &CameraSection::specifyGimbalChanged, this, &CameraSection::_updateSpecifiedGimbalYaw); connect(&_gimbalYawFact, &Fact::valueChanged, this, &CameraSection::_updateSpecifiedGimbalYaw); } diff --git a/src/MissionManager/CameraSection.h b/src/MissionManager/CameraSection.h index e053847..daedda5 100644 --- a/src/MissionManager/CameraSection.h +++ b/src/MissionManager/CameraSection.h @@ -63,6 +63,7 @@ public: void setSpecifyGimbal (bool specifyGimbal); void setSpecifyCameraMode (bool specifyCameraMode); + ///< Signals specifiedGimbalYawChanged ///< @return The gimbal yaw specified by this item, NaN if not specified double specifiedGimbalYaw(void) const; diff --git a/src/MissionManager/MissionSettingsItem.cc b/src/MissionManager/MissionSettingsItem.cc index a19412b..982d440 100644 --- a/src/MissionManager/MissionSettingsItem.cc +++ b/src/MissionManager/MissionSettingsItem.cc @@ -61,8 +61,8 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent) connect(&_cameraSection, &CameraSection::dirtyChanged, this, &MissionSettingsItem::_sectionDirtyChanged); connect(&_speedSection, &SpeedSection::dirtyChanged, this, &MissionSettingsItem::_sectionDirtyChanged); - connect(&_cameraSection, &CameraSection::specifyGimbalChanged, this, &MissionSettingsItem::specifiedGimbalYawChanged); connect(&_cameraSection, &CameraSection::specifiedGimbalYawChanged, this, &MissionSettingsItem::specifiedGimbalYawChanged); + connect(&_speedSection, &SpeedSection::specifiedFlightSpeedChanged, this, &MissionSettingsItem::specifiedFlightSpeedChanged); } diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index d747a4e..9a67255 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -755,13 +755,11 @@ void SimpleMissionItem::_updateOptionalSections(void) connect(_cameraSection, &CameraSection::dirtyChanged, this, &SimpleMissionItem::_sectionDirtyChanged); connect(_cameraSection, &CameraSection::itemCountChanged, this, &SimpleMissionItem::_updateLastSequenceNumber); connect(_cameraSection, &CameraSection::availableChanged, this, &SimpleMissionItem::specifiedGimbalYawChanged); - connect(_cameraSection, &CameraSection::specifyGimbalChanged, this, &SimpleMissionItem::specifiedGimbalYawChanged); connect(_cameraSection, &CameraSection::specifiedGimbalYawChanged, this, &SimpleMissionItem::specifiedGimbalYawChanged); - connect(_speedSection, &SpeedSection::dirtyChanged, this, &SimpleMissionItem::_sectionDirtyChanged); - connect(_speedSection, &SpeedSection::itemCountChanged, this, &SimpleMissionItem::_updateLastSequenceNumber); - connect(_speedSection, &SpeedSection::specifyFlightSpeedChanged, this, &SimpleMissionItem::specifiedFlightSpeedChanged); - connect(_speedSection->flightSpeed(), &Fact::rawValueChanged, this, &SimpleMissionItem::specifiedFlightSpeedChanged); + connect(_speedSection, &SpeedSection::dirtyChanged, this, &SimpleMissionItem::_sectionDirtyChanged); + connect(_speedSection, &SpeedSection::itemCountChanged, this, &SimpleMissionItem::_updateLastSequenceNumber); + connect(_speedSection, &SpeedSection::specifiedFlightSpeedChanged, this, &SimpleMissionItem::specifiedFlightSpeedChanged); emit cameraSectionChanged(_cameraSection); emit speedSectionChanged(_speedSection); diff --git a/src/MissionManager/SpeedSection.cc b/src/MissionManager/SpeedSection.cc index 7979690..6f465a3 100644 --- a/src/MissionManager/SpeedSection.cc +++ b/src/MissionManager/SpeedSection.cc @@ -38,8 +38,11 @@ SpeedSection::SpeedSection(Vehicle* vehicle, QObject* parent) _flightSpeedFact.setMetaData(_metaDataMap[_flightSpeedName]); _flightSpeedFact.setRawValue(flightSpeed); - connect(this, &SpeedSection::specifyFlightSpeedChanged, this, &SpeedSection::settingsSpecifiedChanged); - connect(&_flightSpeedFact, &Fact::valueChanged, this, &SpeedSection::_setDirty); + connect(this, &SpeedSection::specifyFlightSpeedChanged, this, &SpeedSection::settingsSpecifiedChanged); + connect(&_flightSpeedFact, &Fact::valueChanged, this, &SpeedSection::_setDirty); + + connect(this, &SpeedSection::specifyFlightSpeedChanged, this, &SpeedSection::_updateSpecifiedFlightSpeed); + connect(&_flightSpeedFact, &Fact::valueChanged, this, &SpeedSection::_updateSpecifiedFlightSpeed); } bool SpeedSection::settingsSpecified(void) const @@ -134,3 +137,15 @@ bool SpeedSection::scanForSection(QmlObjectListModel* visualItems, int scanIndex return false; } + + +double SpeedSection::specifiedFlightSpeed(void) const +{ + return _specifyFlightSpeed ? _flightSpeedFact.rawValue().toDouble() : std::numeric_limits::quiet_NaN(); +} + +void SpeedSection::_updateSpecifiedFlightSpeed(void) +{ + emit specifiedFlightSpeedChanged(specifiedFlightSpeed()); +} + diff --git a/src/MissionManager/SpeedSection.h b/src/MissionManager/SpeedSection.h index 83069d5..1b37b8f 100644 --- a/src/MissionManager/SpeedSection.h +++ b/src/MissionManager/SpeedSection.h @@ -27,6 +27,10 @@ public: Fact* flightSpeed (void) { return &_flightSpeedFact; } void setSpecifyFlightSpeed (bool specifyFlightSpeed); + ///< Signals specifiedFlightSpeedChanged + ///< @return The flight speed specified by this item, NaN if not specified + double specifiedFlightSpeed(void) const; + // Overrides from Section bool available (void) const override { return _available; } bool dirty (void) const override { return _dirty; } @@ -38,10 +42,12 @@ public: bool settingsSpecified (void) const override; signals: - void specifyFlightSpeedChanged(bool specifyFlightSpeed); + void specifyFlightSpeedChanged (bool specifyFlightSpeed); + void specifiedFlightSpeedChanged (double flightSpeed); private slots: - void _setDirty(void); + void _setDirty (void); + void _updateSpecifiedFlightSpeed(void); private: bool _available; From 01a49a4ce3e9a53298c3d112f49f2a648df78a6c Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Sat, 19 Aug 2017 14:19:05 -0700 Subject: [PATCH 08/12] Anal logging to track down resume mission state problem --- src/FlightDisplay/GuidedActionsController.qml | 23 +++++++++++++++++------ 1 file changed, 17 insertions(+), 6 deletions(-) diff --git a/src/FlightDisplay/GuidedActionsController.qml b/src/FlightDisplay/GuidedActionsController.qml index 33604e7..759bc69 100644 --- a/src/FlightDisplay/GuidedActionsController.qml +++ b/src/FlightDisplay/GuidedActionsController.qml @@ -125,8 +125,7 @@ Item { property bool __pauseVehicleSupported: _activeVehicle ? _activeVehicle.pauseVehicleSupported : false property bool __flightMode: _flightMode - /* - Leaving this code in for use while debugging + // Hack debugging code function _outputState() { console.log(qsTr("_activeVehicle(%1) _vehicleArmed(%2) guidedModeSupported(%3) _vehicleFlying(%4) _vehicleInRTLMode(%5) pauseVehicleSupported(%6) _vehiclePaused(%7) _flightMode(%8)").arg(_activeVehicle ? 1 : 0).arg(_vehicleArmed ? 1 : 0).arg(__guidedModeSupported ? 1 : 0).arg(_vehicleFlying ? 1 : 0).arg(_vehicleInRTLMode ? 1 : 0).arg(__pauseVehicleSupported ? 1 : 0).arg(_vehiclePaused ? 1 : 0).arg(_flightMode)) } @@ -140,11 +139,25 @@ Item { on__GuidedModeSupportedChanged: _outputState() on__PauseVehicleSupportedChanged: _outputState() + on_CurrentMissionIndexChanged: console.log("_currentMissionIndex", _currentMissionIndex) + on_ResumeMissionIndexChanged: console.log("_resumeMissionIndex", _resumeMissionIndex) + onShowResumeMissionChanged: { + console.log("showResumeMission", showResumeMission) + _outputState() + } + onShowStartMissionChanged: { + console.log("showStartMission", showStartMission) + _outputState() + } + onShowContinueMissionChanged: { + console.log("showContinueMission", showContinueMission) + _outputState() + } + // End of hack - */ on_VehicleFlyingChanged: { - //_outputState() + _outputState() if (!_vehicleFlying) { // We use _vehicleWasFLying to help trigger Resume Mission only if the vehicle actually flew and came back down. // Otherwise it may trigger during the Start Mission sequence due to signal ordering or armed and resume mission index. @@ -153,8 +166,6 @@ Item { } property var _actionData - on_CurrentMissionIndexChanged: console.log("_currentMissionIndex", _currentMissionIndex) - on_FlightModeChanged: { _vehiclePaused = _flightMode === _activeVehicle.pauseFlightMode _vehicleInRTLMode = _flightMode === _activeVehicle.rtlFlightMode From 3c7c305491fdb62158aac4344932f36969a777d0 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Sun, 20 Aug 2017 07:34:43 -0700 Subject: [PATCH 09/12] Rename modes for usability --- src/MissionManager/CameraSection.FactMetaData.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/MissionManager/CameraSection.FactMetaData.json b/src/MissionManager/CameraSection.FactMetaData.json index b35c376..c5a0b6b 100644 --- a/src/MissionManager/CameraSection.FactMetaData.json +++ b/src/MissionManager/CameraSection.FactMetaData.json @@ -49,7 +49,7 @@ "name": "CameraMode", "shortDescription": "Specify whether the camera should switch to photo or video mode", "type": "uint32", - "enumStrings": "Take photos,Record video", + "enumStrings": "Photo,Video", "enumValues": "0,1", "defaultValue": 0 } From 57243b55c6d4f4bad5ec10ee15f06e3545fa7438 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Tue, 22 Aug 2017 11:41:21 -0700 Subject: [PATCH 10/12] Add mission property --- src/QmlControls/AppMessages.qml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/QmlControls/AppMessages.qml b/src/QmlControls/AppMessages.qml index 45816d7..ca82d67 100644 --- a/src/QmlControls/AppMessages.qml +++ b/src/QmlControls/AppMessages.qml @@ -24,6 +24,8 @@ QGCView { property bool loaded: false + property var _qgcView: qgcView + QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled } Component { @@ -117,6 +119,7 @@ QGCView { nameFilters: [qsTr("Log files (*.txt)"), qsTr("All Files (*)")] selectExisting: false title: qsTr("Select log save file") + qgcView: _qgcView onAcceptedForSave: { debugMessageModel.writeMessages(file); visible = false; From c8416a227d5a22cd4d5511c26a599d7541ad3db7 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 22 Aug 2017 21:03:31 -0700 Subject: [PATCH 11/12] Resume Mission: Fix up sequence numbers and current item --- src/MissionManager/MissionManager.cc | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index f027f2d..ae18e8f 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -1006,7 +1006,6 @@ void MissionManager::generateResumeMission(int resumeIndex) } resumeIndex = qMax(0, resumeIndex); - int seqNum = 0; QList resumeMission; QList includedResumeCommands; @@ -1029,7 +1028,6 @@ void MissionManager::generateResumeMission(int resumeIndex) << MAV_CMD_NAV_TAKEOFF; bool addHomePosition = _vehicle->firmwarePlugin()->sendHomePositionToVehicle(); - int setCurrentIndex = addHomePosition ? 1 : 0; int prefixCommandCount = 0; for (int i=0; i<_missionItems.count(); i++) { @@ -1039,8 +1037,7 @@ void MissionManager::generateResumeMission(int resumeIndex) prefixCommandCount++; } MissionItem* newItem = new MissionItem(*oldItem, this); - newItem->setIsCurrentItem( i == setCurrentIndex); - newItem->setSequenceNumber(seqNum++); + newItem->setIsCurrentItem(false); resumeMission.append(newItem); } } @@ -1096,6 +1093,14 @@ void MissionManager::generateResumeMission(int resumeIndex) prefixCommandCount--; } + // Adjust sequence numbers and current item + int seqNum = 0; + for (int i=0; isetSequenceNumber(seqNum++); + } + int setCurrentIndex = addHomePosition ? 1 : 0; + resumeMission[setCurrentIndex]->setIsCurrentItem(true); + // Send to vehicle _clearAndDeleteWriteMissionItems(); for (int i=0; i Date: Tue, 22 Aug 2017 21:19:33 -0700 Subject: [PATCH 12/12] Fix de-dup --- src/MissionManager/MissionManager.cc | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index ae18e8f..2fa4cd4 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -1076,12 +1076,13 @@ void MissionManager::generateResumeMission(int resumeIndex) foundCameraStartStop = true; break; case MAV_CMD_IMAGE_START_CAPTURE: - // Only keep the first of these commands that are found - if (foundCameraStartStop) { + if (resumeItem->param3() != 0) { + // Remove commands which do not trigger by time resumeMission.removeAt(prefixCommandCount); + break; } - if (resumeItem->param3() != 0) { - // Remove commands which do no trigger by time + if (foundCameraStartStop) { + // Only keep the first of these commands that are found resumeMission.removeAt(prefixCommandCount); } foundCameraStartStop = true;