From f227844cf3e1409a8aab91f22b58f8c4f59885a7 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Thu, 5 Mar 2020 08:43:06 -0800 Subject: [PATCH 01/16] Added correct handling of mavlink 2 change based on capability bits --- src/Vehicle/Vehicle.cc | 71 ++++++++++++++++++++++++++++++++++---------------- src/Vehicle/Vehicle.h | 17 +++++++----- 2 files changed, 59 insertions(+), 29 deletions(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index f490433..9803371 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -146,10 +146,6 @@ Vehicle::Vehicle(LinkInterface* link, , _telemetryTXBuffer(0) , _telemetryLNoise(0) , _telemetryRNoise(0) - , _mavlinkProtocolRequestComplete(false) - , _maxProtoVersion(0) - , _vehicleCapabilitiesKnown(false) - , _capabilityBits(0) , _highLatencyLink(false) , _receivingAttitudeQuaternion(false) , _cameras(nullptr) @@ -349,7 +345,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, , _defaultHoverSpeed(_settingsManager->appSettings()->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) @@ -692,6 +688,30 @@ 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) { + if (++_capabilitiesRetryCount > 5) { + qgcApp()->showMessage(QStringLiteral("Vehicle failed to send AUTOPILOT_VERSION")); + _handleUnsupportedRequestAutopilotCapabilities(); + } else { + // Vehicle never sent us AUTOPILOT_VERSION response. Try again. + qCDebug(VehicleLog) << "Sending MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES again due to no response with AUTOPILOT_VERSION - _capabilitiesRetryCount" << _capabilitiesRetryCount; + 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); @@ -1288,7 +1308,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); @@ -1300,6 +1320,8 @@ void Vehicle::_setCapabilities(uint64_t capabilityBits) qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_COMMAND_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_COMMAND_INT ? supports : doesNotSupport); 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); + + _setMaxProtoVersionFromBothSources(); } void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& message) @@ -1362,8 +1384,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(); } @@ -1377,6 +1400,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; @@ -2600,7 +2636,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()) { @@ -2619,7 +2655,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"; @@ -3384,19 +3420,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(); @@ -3407,8 +3433,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 7b56c07..2ce4a9d 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -1078,7 +1078,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; } @@ -1096,7 +1096,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(); @@ -1406,9 +1407,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; @@ -1428,8 +1430,9 @@ private: QList _mavCommandQueue; QTimer _mavCommandAckTimer; int _mavCommandRetryCount; - static const int _mavCommandMaxRetryCount = 3; - static const int _mavCommandAckTimeoutMSecs = 3000; + int _capabilitiesRetryCount = 0; + static const int _mavCommandMaxRetryCount = 3; + static const int _mavCommandAckTimeoutMSecs = 3000; static const int _mavCommandAckTimeoutMSecsHighLatency = 120000; QString _prearmError; From ba31ed3f24fe08100b4a0713b52d82bd5cad54ae Mon Sep 17 00:00:00 2001 From: DoinLakeFlyer Date: Thu, 5 Mar 2020 10:30:26 -0800 Subject: [PATCH 02/16] Clear wizard mode when loading from file --- src/MissionManager/TakeoffMissionItem.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/MissionManager/TakeoffMissionItem.cc b/src/MissionManager/TakeoffMissionItem.cc index a03306e..64dadaa 100644 --- a/src/MissionManager/TakeoffMissionItem.cc +++ b/src/MissionManager/TakeoffMissionItem.cc @@ -71,7 +71,7 @@ void TakeoffMissionItem::_init(void) _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()) { @@ -148,6 +148,7 @@ bool TakeoffMissionItem::load(const QJsonObject& json, int sequenceNumber, QStri if (success) { _initLaunchTakeoffAtSameLocation(); } + _wizardMode = false; // Should always be off for loaded items return success; } From 685cb036ad7168e8b3d29c40f94c867edb329863 Mon Sep 17 00:00:00 2001 From: DoinLakeFlyer Date: Thu, 5 Mar 2020 10:40:16 -0800 Subject: [PATCH 03/16] Wizard mode should be off for loaded items --- src/MissionManager/TakeoffMissionItem.cc | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/MissionManager/TakeoffMissionItem.cc b/src/MissionManager/TakeoffMissionItem.cc index 64dadaa..8d5d981 100644 --- a/src/MissionManager/TakeoffMissionItem.cc +++ b/src/MissionManager/TakeoffMissionItem.cc @@ -39,6 +39,7 @@ TakeoffMissionItem::TakeoffMissionItem(const MissionItem& missionItem, Vehicle* , _settingsItem (settingsItem) { _init(); + _wizardMode = false; } TakeoffMissionItem::~TakeoffMissionItem() @@ -139,6 +140,7 @@ bool TakeoffMissionItem::load(QTextStream &loadStream) if (success) { _initLaunchTakeoffAtSameLocation(); } + _wizardMode = false; // Always be off for loaded items return success; } @@ -148,7 +150,7 @@ bool TakeoffMissionItem::load(const QJsonObject& json, int sequenceNumber, QStri if (success) { _initLaunchTakeoffAtSameLocation(); } - _wizardMode = false; // Should always be off for loaded items + _wizardMode = false; // Always be off for loaded items return success; } From 8ff3985bc0542b2e381ff23e769311d15b09ae0e Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 6 Mar 2020 10:12:16 -0800 Subject: [PATCH 04/16] Give up on getting AUTOPILOT_VERSION based on time now retry count. --- src/Vehicle/Vehicle.cc | 8 ++++++-- src/Vehicle/Vehicle.h | 2 ++ 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 9803371..cd824d5 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -698,12 +698,16 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes } } if (!foundRequest) { - if (++_capabilitiesRetryCount > 5) { + _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")); _handleUnsupportedRequestAutopilotCapabilities(); } else { // Vehicle never sent us AUTOPILOT_VERSION response. Try again. - qCDebug(VehicleLog) << "Sending MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES again due to no response with AUTOPILOT_VERSION - _capabilitiesRetryCount" << _capabilitiesRetryCount; + 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 diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 2ce4a9d..7e87789 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" @@ -1431,6 +1432,7 @@ private: QTimer _mavCommandAckTimer; int _mavCommandRetryCount; int _capabilitiesRetryCount = 0; + QTime _capabilitiesRetryElapsed; static const int _mavCommandMaxRetryCount = 3; static const int _mavCommandAckTimeoutMSecs = 3000; static const int _mavCommandAckTimeoutMSecsHighLatency = 120000; From 01dedcc8f9f00ec679adfaae762d3744524a9db4 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 6 Mar 2020 10:17:20 -0800 Subject: [PATCH 05/16] Better error text --- src/Vehicle/Vehicle.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index cd824d5..c4bc18d 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -703,7 +703,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes _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")); + 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. From a2a946d5ed0296be918531c77e784d77f08446e5 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 6 Mar 2020 11:12:40 -0800 Subject: [PATCH 06/16] Programmatic switch to SetupView leaves two buttons selected --- src/ui/toolbar/MainToolBar.qml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/ui/toolbar/MainToolBar.qml b/src/ui/toolbar/MainToolBar.qml index 2e6eaf1..fb6dd69 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 } } From f3072b2a908073ceddf2367fae6030355be8f626 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 6 Mar 2020 12:01:05 -0800 Subject: [PATCH 07/16] Shape file examples for testing --- src/MissionManager/UnitTest/MP 19.prj | 1 + src/MissionManager/UnitTest/MP 19.shp | Bin 0 -> 236 bytes src/MissionManager/UnitTest/MP 19.shx | Bin 0 -> 108 bytes src/MissionManager/UnitTest/MP Bonus.prj | 1 + src/MissionManager/UnitTest/MP Bonus.shp | Bin 0 -> 300 bytes src/MissionManager/UnitTest/MP Bonus.shx | Bin 0 -> 108 bytes src/MissionManager/UnitTest/Sarah's Farm.prj | 1 + src/MissionManager/UnitTest/Sarah's Farm.shp | Bin 0 -> 236 bytes src/MissionManager/UnitTest/Sarah's Farm.shx | Bin 0 -> 108 bytes 9 files changed, 3 insertions(+) create mode 100644 src/MissionManager/UnitTest/MP 19.prj create mode 100644 src/MissionManager/UnitTest/MP 19.shp create mode 100644 src/MissionManager/UnitTest/MP 19.shx create mode 100644 src/MissionManager/UnitTest/MP Bonus.prj create mode 100644 src/MissionManager/UnitTest/MP Bonus.shp create mode 100644 src/MissionManager/UnitTest/MP Bonus.shx create mode 100644 src/MissionManager/UnitTest/Sarah's Farm.prj create mode 100644 src/MissionManager/UnitTest/Sarah's Farm.shp create mode 100644 src/MissionManager/UnitTest/Sarah's Farm.shx diff --git a/src/MissionManager/UnitTest/MP 19.prj b/src/MissionManager/UnitTest/MP 19.prj new file mode 100644 index 0000000..a30c00a --- /dev/null +++ b/src/MissionManager/UnitTest/MP 19.prj @@ -0,0 +1 @@ +GEOGCS["GCS_WGS_1984",DATUM["D_WGS_1984",SPHEROID["WGS_1984",6378137,298.257223563]],PRIMEM["Greenwich",0],UNIT["Degree",0.017453292519943295]] \ No newline at end of file diff --git a/src/MissionManager/UnitTest/MP 19.shp b/src/MissionManager/UnitTest/MP 19.shp new file mode 100644 index 0000000000000000000000000000000000000000..fdb99b041675a81a45765dfe1ba438d93eb3c9a0 GIT binary patch literal 236 zcmZQzQ0HR64$59IGcd3Mlc1 K6j37}F984=@Decq literal 0 HcmV?d00001 diff --git a/src/MissionManager/UnitTest/Sarah's Farm.prj b/src/MissionManager/UnitTest/Sarah's Farm.prj new file mode 100644 index 0000000..a30c00a --- /dev/null +++ b/src/MissionManager/UnitTest/Sarah's Farm.prj @@ -0,0 +1 @@ +GEOGCS["GCS_WGS_1984",DATUM["D_WGS_1984",SPHEROID["WGS_1984",6378137,298.257223563]],PRIMEM["Greenwich",0],UNIT["Degree",0.017453292519943295]] \ No newline at end of file diff --git a/src/MissionManager/UnitTest/Sarah's Farm.shp b/src/MissionManager/UnitTest/Sarah's Farm.shp new file mode 100644 index 0000000000000000000000000000000000000000..cb0985bb0409bdb744912ae39d1a69fa1fa9724c GIT binary patch literal 236 zcmZQzQ0HR64$59IGcd3MV*r2y@X+G-tf6=*NaT`+fq%@-G129%%4v^opfoiP0X DA<{i; literal 0 HcmV?d00001 diff --git a/src/MissionManager/UnitTest/Sarah's Farm.shx b/src/MissionManager/UnitTest/Sarah's Farm.shx new file mode 100644 index 0000000000000000000000000000000000000000..f82d459c668466a4675e6c53b45cb2b078e04ac8 GIT binary patch literal 108 zcmZQzQ0HR64$NLKGcd3M Date: Fri, 6 Mar 2020 12:01:17 -0800 Subject: [PATCH 08/16] Handle multiple file extensions correctly --- src/QmlControls/QGCFileDialog.qml | 12 ++++++------ src/QmlControls/QGCFileDialogController.cc | 22 +++++++++++++++------- src/QmlControls/QGCFileDialogController.h | 4 ++-- 3 files changed, 23 insertions(+), 15 deletions(-) diff --git a/src/QmlControls/QGCFileDialog.qml b/src/QmlControls/QGCFileDialog.qml index fedb66e..06fe48e 100644 --- a/src/QmlControls/QGCFileDialog.qml +++ b/src/QmlControls/QGCFileDialog.qml @@ -117,12 +117,12 @@ Item { onClicked: { hideDialog() - _root.acceptedForLoad(controller.fullyQualifiedFilename(folder, modelData, fileExtension)) + _root.acceptedForLoad(controller.fullyQualifiedFilename(folder, modelData, _rgExtensions)) } onHamburgerClicked: { highlight = true - hamburgerMenu.fileToDelete = controller.fullyQualifiedFilename(folder, modelData, fileExtension) + hamburgerMenu.fileToDelete = controller.fullyQualifiedFilename(folder, modelData, _rgExtensions) hamburgerMenu.popup() } @@ -162,12 +162,12 @@ Item { return } if (!replaceMessage.visible) { - if (controller.fileExists(controller.fullyQualifiedFilename(folder, filenameTextField.text, fileExtension))) { + if (controller.fileExists(controller.fullyQualifiedFilename(folder, filenameTextField.text, _rgExtensions))) { replaceMessage.visible = true return } } - _root.acceptedForSave(controller.fullyQualifiedFilename(folder, filenameTextField.text, fileExtension)) + _root.acceptedForSave(controller.fullyQualifiedFilename(folder, filenameTextField.text, _rgExtensions)) hideDialog() } @@ -230,12 +230,12 @@ Item { onClicked: { hideDialog() - _root.acceptedForSave(controller.fullyQualifiedFilename(folder, modelData, fileExtension)) + _root.acceptedForSave(controller.fullyQualifiedFilename(folder, modelData, _rgExtensions)) } onHamburgerClicked: { highlight = true - hamburgerMenu.fileToDelete = controller.fullyQualifiedFilename(folder, modelData, fileExtension) + hamburgerMenu.fileToDelete = controller.fullyQualifiedFilename(folder, modelData, _rgExtensions) hamburgerMenu.popup() } diff --git a/src/QmlControls/QGCFileDialogController.cc b/src/QmlControls/QGCFileDialogController.cc index f5528df..375fbd3 100644 --- a/src/QmlControls/QGCFileDialogController.cc +++ b/src/QmlControls/QGCFileDialogController.cc @@ -38,16 +38,24 @@ QStringList QGCFileDialogController::getFiles(const QString& directoryPath, cons return files; } -QString QGCFileDialogController::filenameWithExtension(const QString& filename, const QString& fileExtension) +QString QGCFileDialogController::filenameWithExtension(const QString& filename, const QStringList& rgFileExtensions) { QString filenameWithExtension(filename); - QString correctExtension = QString(".%1").arg(fileExtension); - if (!filenameWithExtension.endsWith(correctExtension)) { - filenameWithExtension += correctExtension; + bool matchFound = false; + for (const QString& extension : rgFileExtensions) { + QString dotExtension = QString(".%1").arg(extension); + matchFound = filenameWithExtension.endsWith(dotExtension); + if (matchFound) { + break; + } } - return filenameWithExtension; + if (!matchFound) { + filenameWithExtension += rgFileExtensions[0]; + } + +return filenameWithExtension; } bool QGCFileDialogController::fileExists(const QString& filename) @@ -55,9 +63,9 @@ bool QGCFileDialogController::fileExists(const QString& filename) return QFile(filename).exists(); } -QString QGCFileDialogController::fullyQualifiedFilename(const QString& directoryPath, const QString& filename, const QString& fileExtension) +QString QGCFileDialogController::fullyQualifiedFilename(const QString& directoryPath, const QString& filename, const QStringList& rgFileExtensions) { - return directoryPath + QStringLiteral("/") + filenameWithExtension(filename, fileExtension); + return directoryPath + QStringLiteral("/") + filenameWithExtension(filename, rgFileExtensions); } void QGCFileDialogController::deleteFile(const QString& filename) diff --git a/src/QmlControls/QGCFileDialogController.h b/src/QmlControls/QGCFileDialogController.h index 209a483..4e80503 100644 --- a/src/QmlControls/QGCFileDialogController.h +++ b/src/QmlControls/QGCFileDialogController.h @@ -27,10 +27,10 @@ public: Q_INVOKABLE QStringList getFiles(const QString& directoryPath, const QStringList& fileExtensions); /// Returns the specified file name with the extension added it needed - Q_INVOKABLE QString filenameWithExtension(const QString& filename, const QString& fileExtension); + Q_INVOKABLE QString filenameWithExtension(const QString& filename, const QStringList& rgFileExtensions); /// Returns the fully qualified file name from the specified parts - Q_INVOKABLE QString fullyQualifiedFilename(const QString& directoryPath, const QString& filename, const QString& fileExtension); + Q_INVOKABLE QString fullyQualifiedFilename(const QString& directoryPath, const QString& filename, const QStringList& rgFileExtensions); /// Check for file existence of specified fully qualified file name Q_INVOKABLE bool fileExists(const QString& filename); From 294f086d6cd27e904bcc5564a9e5eff2c25129b7 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sat, 7 Mar 2020 11:26:36 -0800 Subject: [PATCH 09/16] Update --- ChangeLog.md | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/ChangeLog.md b/ChangeLog.md index 1257e8d..79ab04b 100644 --- a/ChangeLog.md +++ b/ChangeLog.md @@ -4,14 +4,22 @@ Note: This file only contains high level features or important fixes. ## 4.0 -### 4.0.1 - Not yet released +### 4.0.3 - Not yet released + +### 4.0.2 - Stable + +* Fix Mavlink V2 protocol negotation based on capability bits +* Fix waiting for AUTOPILOT_VERSION response to get capability bits +* ArduPilot: Above two fixes make fence/rally support enabling more reliable + +### 4.0.1 * 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 - Stable +### 4.0.0 * Added ROI option during manual flight. * Windows: Move builds to 64 bit, Qt 5.12.5 From ef29f8c16e3d3f8cd7350184918a5a0875f8e33a Mon Sep 17 00:00:00 2001 From: DoinLakeFlyer Date: Sat, 7 Mar 2020 12:03:30 -0800 Subject: [PATCH 10/16] Plan: Add support for takeoff item required --- ChangeLog.md | 6 ++++++ src/MissionManager/MissionController.cc | 16 ++++++++++++++++ src/MissionManager/MissionController.h | 10 ++++++++-- src/PlanView/PlanView.qml | 2 +- src/Settings/PlanView.SettingsGroup.json | 6 ++++++ src/Settings/PlanViewSettings.cc | 1 + src/Settings/PlanViewSettings.h | 1 + src/ui/preferences/GeneralSettings.qml | 9 ++++++++- 8 files changed, 47 insertions(+), 4 deletions(-) diff --git a/ChangeLog.md b/ChangeLog.md index 79ab04b..e945753 100644 --- a/ChangeLog.md +++ b/ChangeLog.md @@ -6,6 +6,12 @@ Note: This file only contains high level features or important fixes. ### 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 diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 0feb865..57e142f 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 @@ -59,6 +60,7 @@ const QString MissionController::patternCorridorScanName (QT_TRANSLATE_NOOP(" MissionController::MissionController(PlanMasterController* masterController, QObject *parent) : PlanElementController (masterController, parent) + , _planViewSettings (qgcApp()->toolbox()->settingsManager()->planViewSettings()) , _missionManager (_managerVehicle->missionManager()) , _missionItemCount (0) , _visualItems (nullptr) @@ -77,6 +79,8 @@ MissionController::MissionController(PlanMasterController* masterController, QOb managerVehicleChanged(_managerVehicle); _updateTimer.setSingleShot(true); connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout); + + connect(_planViewSettings->takeoffItemNotRequired(), &Fact::rawValueChanged, this, &MissionController::_takeoffItemNotRequiredChanged); } MissionController::~MissionController() @@ -2301,6 +2305,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; @@ -2430,10 +2435,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(); @@ -2531,3 +2541,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 d72f528..5ab8926 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) @@ -264,6 +266,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 _updateTimeout (void); void _complexBoundingBoxChanged (void); void _recalcAll (void); + void _takeoffItemNotRequiredChanged (void); private: void _init(void); @@ -329,6 +333,7 @@ private: CoordinateVector* _createCoordinateVectorWorker(VisualItemPair& pair); private: + PlanViewSettings* _planViewSettings = nullptr; MissionManager* _missionManager; int _missionItemCount; QmlObjectListModel* _visualItems; @@ -352,10 +357,11 @@ private: QGeoCoordinate _takeoffCoordinate; QGeoCoordinate _previousCoordinate; CoordinateVector* _splitSegment; + 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/PlanView/PlanView.qml b/src/PlanView/PlanView.qml index 0d9e5ed..399cea5 100644 --- a/src/PlanView/PlanView.qml +++ b/src/PlanView/PlanView.qml @@ -617,7 +617,7 @@ Item { { name: _missionController.isROIActive ? qsTr("Cancel ROI") : qsTr("ROI"), iconSource: "/qmlimages/MapAddMission.svg", - buttonEnabled: true, + buttonEnabled: !_missionController.onlyInsertTakeoffValid, buttonVisible: _isMissionLayer && _planMasterController.controllerVehicle.roiModeSupported, toggle: !_missionController.isROIActive }, diff --git a/src/Settings/PlanView.SettingsGroup.json b/src/Settings/PlanView.SettingsGroup.json index eb1921d..53a1cf3 100644 --- a/src/Settings/PlanView.SettingsGroup.json +++ b/src/Settings/PlanView.SettingsGroup.json @@ -16,5 +16,11 @@ "shortDescription": "Show/Hide the mission item status display", "type": "bool", "defaultValue": false +}, +{ + "name": "takeoffItemNotRequired", + "shortDescription": "Allow missions to not require a takeoff item", + "type": "bool", + "defaultValue": false } ] diff --git a/src/Settings/PlanViewSettings.cc b/src/Settings/PlanViewSettings.cc index 8f82dc0..7943178 100644 --- a/src/Settings/PlanViewSettings.cc +++ b/src/Settings/PlanViewSettings.cc @@ -20,3 +20,4 @@ DECLARE_SETTINGGROUP(PlanView, "PlanView") DECLARE_SETTINGSFACT(PlanViewSettings, displayPresetsTabFirst) DECLARE_SETTINGSFACT(PlanViewSettings, aboveTerrainWarning) DECLARE_SETTINGSFACT(PlanViewSettings, showMissionItemStatus) +DECLARE_SETTINGSFACT(PlanViewSettings, takeoffItemNotRequired) diff --git a/src/Settings/PlanViewSettings.h b/src/Settings/PlanViewSettings.h index 2fbc3bd..83d4c34 100644 --- a/src/Settings/PlanViewSettings.h +++ b/src/Settings/PlanViewSettings.h @@ -23,4 +23,5 @@ public: DEFINE_SETTINGFACT(displayPresetsTabFirst) DEFINE_SETTINGFACT(aboveTerrainWarning) DEFINE_SETTINGFACT(showMissionItemStatus) + DEFINE_SETTINGFACT(takeoffItemNotRequired) }; diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index 3897dc6..c6e54ed 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) @@ -621,6 +622,12 @@ Rectangle { fact: QGroundControl.settingsManager.appSettings.defaultMissionItemAltitude } } + + FactCheckBox { + text: qsTr("Missions Do Not Require Takeoff Item") + fact: _planViewSettings.takeoffItemNotRequired + visible: _planViewSettings.takeoffItemNotRequired.visible + } } } From cd6803a795957157c2f70ebc9f45f351139b2c5c Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Sat, 7 Mar 2020 17:01:19 -0700 Subject: [PATCH 11/16] fixed preflight sensors check --- src/FlightDisplay/PreFlightSensorsHealthCheck.qml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/FlightDisplay/PreFlightSensorsHealthCheck.qml b/src/FlightDisplay/PreFlightSensorsHealthCheck.qml index 1d04ad1..e5e4a2a 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 | From 26a897bb4995f3859066277dfa186c8564154fa3 Mon Sep 17 00:00:00 2001 From: Andrew Voznytsa Date: Sun, 8 Mar 2020 16:51:50 +0200 Subject: [PATCH 12/16] Add EGL to gstreamer dependecies --- CMakeLists.txt | 1 + src/VideoStreaming/VideoStreaming.pri | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5f60bf2..e2f00e7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -88,6 +88,7 @@ pkg_check_modules(GST gstreamer-1.0>=1.14 gstreamer-video-1.0>=1.14 gstreamer-gl-1.0>=1.14 + egl ) if (GST_FOUND) diff --git a/src/VideoStreaming/VideoStreaming.pri b/src/VideoStreaming/VideoStreaming.pri index b015399..b1af89f 100644 --- a/src/VideoStreaming/VideoStreaming.pri +++ b/src/VideoStreaming/VideoStreaming.pri @@ -15,7 +15,7 @@ LinuxBuild { QT += x11extras waylandclient CONFIG += link_pkgconfig packagesExist(gstreamer-1.0) { - PKGCONFIG += gstreamer-1.0 gstreamer-video-1.0 gstreamer-gl-1.0 + PKGCONFIG += gstreamer-1.0 gstreamer-video-1.0 gstreamer-gl-1.0 egl CONFIG += VideoEnabled } } else:MacBuild { From 5f9c4a2927820a56621b2c1f60e7b25f68888c87 Mon Sep 17 00:00:00 2001 From: Alexey Date: Mon, 9 Mar 2020 11:58:12 +0100 Subject: [PATCH 13/16] Fixed 'if' typo in VideoReceiver::_makeSource method --- src/VideoStreaming/VideoReceiver.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/VideoStreaming/VideoReceiver.cc b/src/VideoStreaming/VideoReceiver.cc index 339da10..321ae04 100644 --- a/src/VideoStreaming/VideoReceiver.cc +++ b/src/VideoStreaming/VideoReceiver.cc @@ -336,7 +336,7 @@ VideoReceiver::_makeSource(const QString& uri) qCCritical(VideoReceiverLog) << "gst_caps_from_string() failed"; break; } - } else if (isUdp264) { + } else if (isUdp265) { if ((caps = gst_caps_from_string("application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H265")) == nullptr) { qCCritical(VideoReceiverLog) << "gst_caps_from_string() failed"; break; From 7e27e066317242cc124587b1ac68d84c8b46ee5f Mon Sep 17 00:00:00 2001 From: Andrew Voznytsa Date: Tue, 10 Mar 2020 10:51:44 +0200 Subject: [PATCH 14/16] Fix MPEG-2 TS recording --- src/VideoStreaming/VideoReceiver.cc | 39 ++++++++++++++++++++++++++----------- 1 file changed, 28 insertions(+), 11 deletions(-) diff --git a/src/VideoStreaming/VideoReceiver.cc b/src/VideoStreaming/VideoReceiver.cc index 321ae04..038b1a7 100644 --- a/src/VideoStreaming/VideoReceiver.cc +++ b/src/VideoStreaming/VideoReceiver.cc @@ -310,6 +310,7 @@ VideoReceiver::_makeSource(const QString& uri) GstElement* source = nullptr; GstElement* buffer = nullptr; + GstElement* tsdemux = nullptr; GstElement* parser = nullptr; GstElement* bin = nullptr; GstElement* srcbin = nullptr; @@ -358,26 +359,37 @@ VideoReceiver::_makeSource(const QString& uri) break; } + if ((bin = gst_bin_new("sourcebin")) == nullptr) { + qCCritical(VideoReceiverLog) << "gst_bin_new('sourcebin') failed"; + break; + } + + if ((parser = gst_element_factory_make("parsebin", "parser")) == nullptr) { + qCCritical(VideoReceiverLog) << "gst_element_factory_make('parsebin') failed"; + break; + } + + gst_bin_add_many(GST_BIN(bin), source, parser, nullptr); + // FIXME: AV: Android does not determine MPEG2-TS via parsebin - have to explicitly state which demux to use + // FIXME: AV: tsdemux handling is a bit ugly - let's try to find elegant solution for that later if (isTcpMPEGTS || isUdpMPEGTS) { - if ((parser = gst_element_factory_make("tsdemux", "parser")) == nullptr) { - qCritical(VideoReceiverLog) << "gst_element_factory_make('tsdemux') failed"; + if ((tsdemux = gst_element_factory_make("tsdemux", nullptr)) == nullptr) { + qCCritical(VideoReceiverLog) << "gst_element_factory_make('tsdemux') failed"; break; } - } else { - if ((parser = gst_element_factory_make("parsebin", "parser")) == nullptr) { - qCritical() << "VideoReceiver::_makeSource() failed. Error with gst_element_factory_make('parsebin')"; + + gst_bin_add(GST_BIN(bin), tsdemux); + + if (!gst_element_link(source, tsdemux)) { + qCCritical(VideoReceiverLog) << "gst_element_link() failed"; break; } - } - if ((bin = gst_bin_new("sourcebin")) == nullptr) { - qCCritical(VideoReceiverLog) << "gst_bin_new('sourcebin') failed"; - break; + source = tsdemux; + tsdemux = nullptr; } - gst_bin_add_many(GST_BIN(bin), source, parser, nullptr); - int probeRes = 0; gst_element_foreach_src_pad(source, _padProbe, &probeRes); @@ -423,6 +435,11 @@ VideoReceiver::_makeSource(const QString& uri) parser = nullptr; } + if (tsdemux != nullptr) { + gst_object_unref(tsdemux); + tsdemux = nullptr; + } + if (buffer != nullptr) { gst_object_unref(buffer); buffer = nullptr; From 7fcc3a02f01fcf6698a351ddb777a7544680bf06 Mon Sep 17 00:00:00 2001 From: DoinLakeFlyer Date: Tue, 10 Mar 2020 14:01:12 -0700 Subject: [PATCH 15/16] Correct handling of terrain ready when loading back from file --- src/MissionManager/CameraSectionTest.cc | 30 +++++++++++++------------- src/MissionManager/FWLandingPatternTest.cc | 4 ++-- src/MissionManager/MissionController.cc | 16 +++++++------- src/MissionManager/MissionItemTest.cc | 4 ++-- src/MissionManager/SimpleMissionItem.cc | 22 +++++++++++++------ src/MissionManager/SimpleMissionItem.h | 3 +-- src/MissionManager/SimpleMissionItemTest.cc | 2 +- src/MissionManager/TakeoffMissionItem.cc | 19 ++++++++++------ src/MissionManager/TakeoffMissionItem.h | 4 ++-- src/MissionManager/TransectStyleComplexItem.cc | 14 +++++++++++- 10 files changed, 71 insertions(+), 47 deletions(-) diff --git a/src/MissionManager/CameraSectionTest.cc b/src/MissionManager/CameraSectionTest.cc index a31bfed..7d35bb7 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(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_offlineVehicle, 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(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidCameraModeItem = new SimpleMissionItem(_offlineVehicle, 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(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_offlineVehicle, 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(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, 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(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_offlineVehicle, 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(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_offlineVehicle, 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(_offlineVehicle, false /* flyView */, this); - SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidStopDistanceItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); + SimpleMissionItem* newValidStopTimeItem = new SimpleMissionItem(_offlineVehicle, 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(_offlineVehicle, false /* flyView */, nullptr); - SimpleMissionItem validStopTimeItem(_offlineVehicle, false /* flyView */, nullptr); + SimpleMissionItem validStopDistanceItem(_offlineVehicle, false /* flyView */, false /* forLoad */, nullptr); + SimpleMissionItem validStopTimeItem(_offlineVehicle, 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(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_offlineVehicle, 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(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); item1->missionItem() = actionItem->missionItem(); - SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, 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(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, this); item1->missionItem() = actionItem->missionItem(); - SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this); + SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, 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 035329b..87f439e 100644 --- a/src/MissionManager/FWLandingPatternTest.cc +++ b/src/MissionManager/FWLandingPatternTest.cc @@ -97,7 +97,7 @@ void FWLandingPatternTest::_testAppendSectionItems(void) QmlObjectListModel* simpleItems = new QmlObjectListModel(this); for (MissionItem* item: rgMissionItems) { - SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, simpleItems); + SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, simpleItems); simpleItem->missionItem() = *item; simpleItems->append(simpleItem); } @@ -118,7 +118,7 @@ void FWLandingPatternTest::_testAppendSectionItems(void) _fwItem->appendMissionItems(rgMissionItems, this); simpleItems = new QmlObjectListModel(this); for (MissionItem* item: rgMissionItems) { - SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, simpleItems); + SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, simpleItems); simpleItem->missionItem() = *item; simpleItems->append(simpleItem); } diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 57e142f..6a221ab 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -359,7 +359,7 @@ int MissionController::_nextSequenceNumber(void) VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex, bool makeCurrentItem) { int sequenceNumber = _nextSequenceNumber(); - SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this); + SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, false /* forLoad */, this); newItem->setSequenceNumber(sequenceNumber); newItem->setCoordinate(coordinate); newItem->setCommand(command); @@ -673,7 +673,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec MissionSettingsItem* settingsItem = _addMissionSettings(visualItems); if (json.contains(_jsonPlannedHomePositionKey)) { - SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems); + SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, true /* forLoad */, visualItems); if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) { settingsItem->setInitialHomePositionFromUser(item->coordinate()); item->deleteLater(); @@ -709,11 +709,11 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec } const QJsonObject itemObject = itemValue.toObject(); - SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems); + SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _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(_controllerVehicle, _flyView, settingsItem, visualItems); + TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, true /* forLoad */, visualItems); takeoffItem->load(itemObject, itemObject["id"].toInt(), errorString); item->deleteLater(); item = takeoffItem; @@ -797,11 +797,11 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec QString itemType = itemObject[VisualMissionItem::jsonTypeKey].toString(); if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) { - SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems); + SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _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(_controllerVehicle, _flyView, settingsItem, this); + TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, true /* forLoad */, this); takeoffItem->load(itemObject, nextSequenceNumber, errorString); simpleItem->deleteLater(); simpleItem = takeoffItem; @@ -941,14 +941,14 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM MissionSettingsItem* settingsItem = _addMissionSettings(visualItems); while (!stream.atEnd()) { - SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems); + SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _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(_controllerVehicle, _flyView, settingsItem, visualItems); + TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, true /* forLoad */, visualItems); takeoffItem->load(stream); item->deleteLater(); item = takeoffItem; diff --git a/src/MissionManager/MissionItemTest.cc b/src/MissionManager/MissionItemTest.cc index ddee6ee..8b43b4d 100644 --- a/src/MissionManager/MissionItemTest.cc +++ b/src/MissionManager/MissionItemTest.cc @@ -281,7 +281,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 */, nullptr); + SimpleMissionItem simpleMissionItem(_offlineVehicle, 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); @@ -451,7 +451,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 */, nullptr); + SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, false /* forLoad */, nullptr); QString errorString; QJsonArray coordinateArray; QJsonObject jsonObject; diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index a5b8531..bd9fa0e 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -51,7 +51,7 @@ static const struct EnumInfo_s _rgMavFrameInfo[] = { { "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT", MAV_FRAME_GLOBAL_TERRAIN_ALT_INT }, }; -SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent) +SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, bool forLoad, QObject* parent) : VisualMissionItem (vehicle, flyView, parent) , _rawEdit (false) , _dirty (false) @@ -75,13 +75,15 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* pa _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(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent) @@ -295,7 +297,10 @@ bool SimpleMissionItem::load(QTextStream &loadStream) _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue()); _amslAltAboveTerrainFact.setRawValue(qQNaN()); } + _connectSignals(); _updateOptionalSections(); + _rebuildFacts(); + setDirty(false); } return success; @@ -328,7 +333,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 ff065dc..a89ab40 100644 --- a/src/MissionManager/SimpleMissionItem.h +++ b/src/MissionManager/SimpleMissionItem.h @@ -24,9 +24,8 @@ class SimpleMissionItem : public VisualMissionItem Q_OBJECT public: - SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent); + SimpleMissionItem(Vehicle* vehicle, bool flyView, bool forLoad, QObject* parent); SimpleMissionItem(Vehicle* vehicle, 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 a5b023d..52296fa 100644 --- a/src/MissionManager/SimpleMissionItemTest.cc +++ b/src/MissionManager/SimpleMissionItemTest.cc @@ -167,7 +167,7 @@ void SimpleMissionItemTest::_testEditorFacts(void) void SimpleMissionItemTest::_testDefaultValues(void) { - SimpleMissionItem item(_offlineVehicle, false /* flyView */, nullptr); + SimpleMissionItem item(_offlineVehicle, 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/TakeoffMissionItem.cc b/src/MissionManager/TakeoffMissionItem.cc index 8d5d981..cb2e03c 100644 --- a/src/MissionManager/TakeoffMissionItem.cc +++ b/src/MissionManager/TakeoffMissionItem.cc @@ -19,26 +19,26 @@ #include "QGroundControlQmlGlobal.h" #include "SettingsManager.h" -TakeoffMissionItem::TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent) - : SimpleMissionItem (vehicle, flyView, parent) +TakeoffMissionItem::TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, bool forLoad, QObject* parent) + : SimpleMissionItem (vehicle, flyView, forLoad, parent) , _settingsItem (settingsItem) { - _init(); + _init(forLoad); } TakeoffMissionItem::TakeoffMissionItem(MAV_CMD takeoffCmd, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent) - : SimpleMissionItem (vehicle, flyView, parent) + : SimpleMissionItem (vehicle, flyView, false /* forLoad */, parent) , _settingsItem (settingsItem) { setCommand(takeoffCmd); - _init(); + _init(false /* forLoad */); } TakeoffMissionItem::TakeoffMissionItem(const MissionItem& missionItem, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent) : SimpleMissionItem (vehicle, flyView, missionItem, parent) , _settingsItem (settingsItem) { - _init(); + _init(false /* forLoad */); _wizardMode = false; } @@ -47,7 +47,7 @@ TakeoffMissionItem::~TakeoffMissionItem() } -void TakeoffMissionItem::_init(void) +void TakeoffMissionItem::_init(bool forLoad) { _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml"); @@ -69,6 +69,11 @@ void TakeoffMissionItem::_init(void) } } + if (forLoad) { + // Load routines will set the rest up after load + return; + } + _initLaunchTakeoffAtSameLocation(); if (homePosition.isValid() && coordinate().isValid()) { diff --git a/src/MissionManager/TakeoffMissionItem.h b/src/MissionManager/TakeoffMissionItem.h index d4f3ce9..843278c 100644 --- a/src/MissionManager/TakeoffMissionItem.h +++ b/src/MissionManager/TakeoffMissionItem.h @@ -19,7 +19,7 @@ class TakeoffMissionItem : public SimpleMissionItem Q_OBJECT public: - TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent); + TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, bool forLoad, QObject* parent); TakeoffMissionItem(MAV_CMD takeoffCmd, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent); TakeoffMissionItem(const MissionItem& missionItem, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent); @@ -55,7 +55,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 ca21c6b..fb2c26f 100644 --- a/src/MissionManager/TransectStyleComplexItem.cc +++ b/src/MissionManager/TransectStyleComplexItem.cc @@ -498,7 +498,19 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList Date: Wed, 11 Mar 2020 09:29:06 -0700 Subject: [PATCH 16/16] Add note about ADSB server settings --- src/ui/preferences/GeneralSettings.qml | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index c6e54ed..125a09b 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -890,16 +890,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