diff --git a/.travis.yml b/.travis.yml index edc1f1979f5c5570aadb466757792611b7d9550f..c4b61d6884abc652808b73b510f37c8ea8573aa9 100644 --- a/.travis.yml +++ b/.travis.yml @@ -225,6 +225,7 @@ before_deploy: deploy: # deploy installers to s3 builds/ if on a branch - provider: s3 + edge: true # Use V2 provider to work around V1 bug access_key_id: AKIAIVORNALE7NHD3T6Q secret_access_key: secure: BsLXeXUPsCJdX4tawrDnO8OFK5Hk4kzlDTiyH93En6TbjUargVAWDMcHVj7TUhr7+3Tao1W1zb0G4SJe9kHv+jrky0yE72KvoG3YAON0VXWKizxBAKkgHE2RxSTNAwDeKbi2G6YJfNDescBBfX7zEohShdXglQu7CGaUQKRaiI4= @@ -255,6 +256,7 @@ deploy: # deploy tagged installers to s3 version folder - provider: s3 + edge: true # Use V2 provider to work around V1 bug access_key_id: AKIAIVORNALE7NHD3T6Q secret_access_key: secure: BsLXeXUPsCJdX4tawrDnO8OFK5Hk4kzlDTiyH93En6TbjUargVAWDMcHVj7TUhr7+3Tao1W1zb0G4SJe9kHv+jrky0yE72KvoG3YAON0VXWKizxBAKkgHE2RxSTNAwDeKbi2G6YJfNDescBBfX7zEohShdXglQu7CGaUQKRaiI4= @@ -270,6 +272,7 @@ deploy: # deploy installers to Github releases if on a tag - provider: releases + edge: true # Use V2 provider to work around V1 bug api-key: secure: K/Zqr/FCC7QvzFxYvBtCinPkacQq2ubJ2qm982+38Zf/KjibVOF1dEbVdrGZmII6Tg5DaQzNXGYkg5PvYmJgT9xRsqeQjeYIUYqYZpAt+HYWA38AVfMU8jip/1P1wmwqD469nzJOBBa8yfsMs6Ca7tBaNl/zTxCRGnAgEzqtkdQ= file_glob: true diff --git a/ChangeLog.md b/ChangeLog.md index 26889a5cd5daaae41dff3f9b3f99d475957335e2..805720edf15c3167096058a667ecefd140d0bd5a 100644 --- a/ChangeLog.md +++ b/ChangeLog.md @@ -2,12 +2,17 @@ Note: This file only contains high level features or important fixes. -## 4.1 - Daily Build +## 4.1 - Daily build * Support mavlink terrain protocol which queries gcs for terrain height information. Allows planning missions with TERRAIN\_FRAME. ## 4.0 +### 4.0.1 - Not yet release + +* Fix ArduPilot current mission item tracking in Fly view +* Fix ADSB vehicle display + ### 4.0.0 - Stable * Added ROI option during manual flight. @@ -19,9 +24,7 @@ Note: This file only contains high level features or important fixes. * Plan View: New create plan UI for initial plan creation * New Corridor editing tools ui. Includes ability to trace polyline by clicking. * New Polygon editing tools ui. Includes ability to trace polygon by clicking. -* ArduCopter/Rover: Follow Me setup page * More performant flight path display algorithm. Mobile builds no longer show limited path length. -* ArduCopter/Rover: Add support for Follow Me * ArduPilot: Add Motor Test vehicle setup page * Compass Instrument: Add indicators for Home, COG and Next Waypoint headings. * Log Replay: Support changing speed of playback @@ -56,9 +59,9 @@ Note: This file only contains high level features or important fixes. * ArduPilot: Support configurable mavlink stream rates. Available from Settings/Mavlink page. * Major rewrite and bug fix pass through Structure Scan. Previous version had such bad problems that it can no longer be supported. Plans with Structure Scan will need to be recreated. New QGC will not load old Structure Scan plans. -### 3.5.6 - Not yet released +## 3.5 -### 3.5.5 - Stable +### 3.5.5 * Fix mavlink message memset which cause wrong commands to be sent on ArduPilot GotoLocation. * Disable Pause when fixed wing is on landing approach. diff --git a/QGCInstaller.pri b/QGCInstaller.pri index 5f25b20cafb3730e5beb388095f7d3f21484520f..80bbd1d38609e8417194b6b648d5409dd2192c35 100644 --- a/QGCInstaller.pri +++ b/QGCInstaller.pri @@ -27,7 +27,7 @@ installer { # We cd to release directory so we can run macdeployqt without a path to the # qgroundcontrol.app file. If you specify a path to the .app file the symbolic # links to plugins will not be created correctly. - QMAKE_POST_LINK += && cd $${DESTDIR} && $$dirname(QMAKE_QMAKE)/macdeployqt $${TARGET}.app -appstore-compliant -verbose=2 -qmldir=$${BASEDIR}/src + QMAKE_POST_LINK += && cd $${DESTDIR} && $$dirname(QMAKE_QMAKE)/macdeployqt $${TARGET}.app -appstore-compliant -verbose=1 -qmldir=$${BASEDIR}/src # macdeployqt is missing some relocations once in a while. "Fix" it: QMAKE_POST_LINK += && python $$BASEDIR/tools/osxrelocator.py $${TARGET}.app/Contents @rpath @executable_path/../Frameworks -r > /dev/null 2>&1 diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc index 5953407073412def3eb8f5933a7eb110c68bbb31..5209e106597d2d04e1e3956148eec0e45359c595 100644 --- a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc @@ -53,7 +53,10 @@ APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent) , _tuningComponent (nullptr) , _esp8266Component (nullptr) , _heliComponent (nullptr) +#if 0 + // Follow me not ready for Stable , _followComponent (nullptr) +#endif { #if !defined(NO_SERIAL_LINK) && !defined(__android__) connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &APMAutoPilotPlugin::_checkForBadCubeBlack); @@ -104,12 +107,16 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) _safetyComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent)); +#if 0 + // Follow me not ready for Stable + if ((qobject_cast(_vehicle->firmwarePlugin()) || qobject_cast(_vehicle->firmwarePlugin())) && _vehicle->parameterManager()->parameterExists(-1, QStringLiteral("FOLL_ENABLE"))) { _followComponent = new APMFollowComponent(_vehicle, this); _followComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_followComponent)); } +#endif if (_vehicle->vehicleType() == MAV_TYPE_HELICOPTER && (_vehicle->versionCompare(4, 0, 0) >= 0)) { _heliComponent = new APMHeliComponent(_vehicle, this); diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h index 28f2166bc22626d78ff715e24c1be19c43fc7def..410fb8be02a939051c438e526672fd4e43c5c1d0 100644 --- a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h @@ -57,7 +57,10 @@ protected: APMTuningComponent* _tuningComponent; ESP8266Component* _esp8266Component; APMHeliComponent* _heliComponent; +#if 0 + // Follow me not ready for Stable APMFollowComponent* _followComponent; +#endif #if !defined(NO_SERIAL_LINK) && !defined(__android__) private slots: diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index 6038b81a8f51897d676ce7c67705ca495fe53f28..3af285e00b90a4e924184072459b985780fee982 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -43,7 +43,10 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) : { GUIDED_NOGPS, "Guided No GPS"}, { SMART_RTL, "Smart RTL"}, { FLOWHOLD, "Flow Hold" }, +#if 0 + // Follow me not ready for Stable { FOLLOW, "Follow" }, +#endif { ZIGZAG, "ZigZag" }, }); } @@ -71,7 +74,10 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void) APMCopterMode(APMCopterMode::GUIDED_NOGPS, true), APMCopterMode(APMCopterMode::SMART_RTL, true), APMCopterMode(APMCopterMode::FLOWHOLD, true), +#if 0 + // Follow me not ready for Stable APMCopterMode(APMCopterMode::FOLLOW, true), +#endif APMCopterMode(APMCopterMode::ZIGZAG, true), }); @@ -141,7 +147,10 @@ bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* return true; } +#if 0 + // Follow me not ready for Stable void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) { _sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities); } +#endif diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h index 9b802a80659bf3f036610ffafa1dc301bfc006fb..05c596994f8964498e2efd3c2f051cd7b679817e 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h @@ -43,7 +43,10 @@ public: GUIDED_NOGPS= 20, SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder +#if 0 + // Follow me not ready for Stable FOLLOW = 23, // follow attempts to follow another vehicle or ground station +#endif ZIGZAG = 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B }; @@ -71,7 +74,10 @@ public: bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const override; QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); } bool supportsSmartRTL (void) const override { return true; } +#if 0 + // Follow me not ready for Stable void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override; +#endif private: static bool _remapParamNameIntialized; diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc index 46a0fe0011702b967db1abf6c33344f5fe5bfe86..0dbef83d0970fff7235478c87968cafb9c85679c 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc @@ -22,7 +22,10 @@ APMRoverMode::APMRoverMode(uint32_t mode, bool settable) {STEERING, "Steering"}, {HOLD, "Hold"}, {LOITER, "Loiter"}, +#if 0 + // Follow me not ready for Stable {FOLLOW, "Follow"}, +#endif {SIMPLE, "Simple"}, {AUTO, "Auto"}, {RTL, "RTL"}, @@ -40,7 +43,10 @@ ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void) APMRoverMode(APMRoverMode::STEERING ,true), APMRoverMode(APMRoverMode::HOLD ,true), APMRoverMode(APMRoverMode::LOITER ,true), +#if 0 + // Follow me not ready for Stable APMRoverMode(APMRoverMode::FOLLOW ,true), +#endif APMRoverMode(APMRoverMode::SIMPLE ,true), APMRoverMode(APMRoverMode::AUTO ,true), APMRoverMode(APMRoverMode::RTL ,true), @@ -78,7 +84,10 @@ bool ArduRoverFirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/) return true; } +#if 0 + // Follow me not ready for Stable void ArduRoverFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) { _sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities); } +#endif diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h index ca29f890ff40fbb46a9f6d76162494689aaab314..1338b3f65b8ea82f69f90fe46dfb392b16844745 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h @@ -25,7 +25,10 @@ public: STEERING = 3, HOLD = 4, LOITER = 5, +#if 0 + // Follow me not ready for Stable FOLLOW = 6, +#endif SIMPLE = 7, AUTO = 10, RTL = 11, @@ -53,7 +56,10 @@ public: bool supportsNegativeThrust (Vehicle *) final; bool supportsSmartRTL (void) const override { return true; } QString offlineEditingParamFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Rover.OfflineEditing.params"); } +#if 0 + // Follow me not ready for Stable void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override; +#endif private: static bool _remapParamNameIntialized; diff --git a/src/FlightDisplay/PreFlightCheckList.qml b/src/FlightDisplay/PreFlightCheckList.qml index af5c2b7d2bdb7084c737bc320ba72fcbcb7ca415..6115e3f7bc8842248392e5571608e20ddee409f8 100644 --- a/src/FlightDisplay/PreFlightCheckList.qml +++ b/src/FlightDisplay/PreFlightCheckList.qml @@ -66,23 +66,25 @@ Rectangle { //-- Pick a checklist model that matches the current airframe type (if any) function _updateModel() { - if(activeVehicle) { - if(activeVehicle.multiRotor) { - modelContainer.source = "/checklists/MultiRotorChecklist.qml" - } else if(activeVehicle.vtol) { - modelContainer.source = "/checklists/VTOLChecklist.qml" - } else if(activeVehicle.rover) { - modelContainer.source = "/checklists/RoverChecklist.qml" - } else if(activeVehicle.sub) { - modelContainer.source = "/checklists/SubChecklist.qml" - } else if(activeVehicle.fixedWing) { - modelContainer.source = "/checklists/FixedWingChecklist.qml" - } else { - modelContainer.source = "/checklists/DefaultChecklist.qml" - } - return + var vehicle = activeVehicle + if (!vehicle) { + vehicle = QGroundControl.multiVehicleManager.offlineEditingVehicle + } + + if(vehicle.multiRotor) { + modelContainer.source = "/checklists/MultiRotorChecklist.qml" + } else if(vehicle.vtol) { + modelContainer.source = "/checklists/VTOLChecklist.qml" + } else if(vehicle.rover) { + modelContainer.source = "/checklists/RoverChecklist.qml" + } else if(vehicle.sub) { + modelContainer.source = "/checklists/SubChecklist.qml" + } else if(vehicle.fixedWing) { + modelContainer.source = "/checklists/FixedWingChecklist.qml" + } else { + modelContainer.source = "/checklists/DefaultChecklist.qml" } - modelContainer.source = "/checklists/DefaultChecklist.qml" + return } Component.onCompleted: { diff --git a/src/FlightMap/Widgets/MapFitFunctions.qml b/src/FlightMap/Widgets/MapFitFunctions.qml index dc3c3d8e567ce4b198de9579d4b54502c4168bd4..b8197994f988a8b5afd1be00bff0c015b17059b5 100644 --- a/src/FlightMap/Widgets/MapFitFunctions.qml +++ b/src/FlightMap/Widgets/MapFitFunctions.qml @@ -62,8 +62,14 @@ Item { var east = normalizeLon(coordList[0].longitude) var west = east for (var i = 1; i < coordList.length; i++) { - var lat = normalizeLat(coordList[i].latitude) - var lon = normalizeLon(coordList[i].longitude) + var lat = coordList[i].latitude + var lon = coordList[i].longitude + 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) north = Math.max(north, lat) south = Math.min(south, lat) east = Math.max(east, lon) @@ -110,19 +116,6 @@ Item { // Being called prior to controller.start return } - /* - for (var i=1; i<_missionController.visualItems.count; i++) { - var missionItem = _missionController.visualItems.get(i) - if (missionItem.specifiesCoordinate && !missionItem.isStandaloneCoordinate) { - console.log(missionItem.boundingCube.pointNW) - console.log(missionItem.boundingCube.pointSE) - var loc = QtPositioning.rectangle(missionItem.boundingCube.pointNW, missionItem.boundingCube.pointSE) - console.log(loc) - map.visibleRegion = loc - return - } - } - */ var coordList = [ ] addMissionItemCoordsForFit(coordList) fitMapViewportToAllCoordinates(coordList) diff --git a/src/MissionManager/ComplexMissionItem.cc b/src/MissionManager/ComplexMissionItem.cc index c7ba840f84ffd9febe7888831eb4be2c417a52fa..0580c1d30b4d4a51d0d1de89bb18d5c1145e87e5 100644 --- a/src/MissionManager/ComplexMissionItem.cc +++ b/src/MissionManager/ComplexMissionItem.cc @@ -21,6 +21,8 @@ const char* ComplexMissionItem::_presetSettingsKey = "_presets"; ComplexMissionItem::ComplexMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent) : VisualMissionItem (masterController, flyView, parent) + , _toolbox (qgcApp()->toolbox()) + , _settingsManager (_toolbox->settingsManager()) { } @@ -75,6 +77,26 @@ void ComplexMissionItem::_savePresetJson(const QString& name, QJsonObject& prese settings.beginGroup(presetsSettingsGroup()); settings.beginGroup(_presetSettingsKey); settings.setValue(name, QJsonDocument(presetObject).toBinaryData()); + + // Use this to save a survey preset as a JSON file to be included in the build + // as a built-in survey preset that cannot be deleted. + #if 0 + QString savePath = _settingsManager->appSettings()->missionSavePath(); + QDir saveDir(savePath); + + QString fileName = saveDir.absoluteFilePath(name); + fileName.append(".json"); + QFile jsonFile(fileName); + + if (!jsonFile.open(QIODevice::WriteOnly)) { + qDebug() << "Couldn't open .json file."; + } + + qDebug() << "Saving survey preset to JSON"; + auto jsonDoc = QJsonDocument(jsonObj); + jsonFile.write(jsonDoc.toJson()); + #endif + emit presetNamesChanged(); } diff --git a/src/MissionManager/ComplexMissionItem.h b/src/MissionManager/ComplexMissionItem.h index 81def4071a52d9c3f894059e758135cbd2a5235c..8133ba32f52ce5e5c26370db0939cfdef638bc3b 100644 --- a/src/MissionManager/ComplexMissionItem.h +++ b/src/MissionManager/ComplexMissionItem.h @@ -11,6 +11,8 @@ #include "VisualMissionItem.h" #include "QGCGeo.h" +#include "QGCToolbox.h" +#include "SettingsManager.h" #include @@ -88,4 +90,7 @@ protected: QMap _metaDataMap; static const char* _presetSettingsKey; + + QGCToolbox* _toolbox; + SettingsManager* _settingsManager; }; diff --git a/src/QmlControls/ToolStrip.qml b/src/QmlControls/ToolStrip.qml index 87374c55ee27b54bb98a24b5958c3e5106b4ef46..067928fb44a7dd4925660b621684b6024580901e 100644 --- a/src/QmlControls/ToolStrip.qml +++ b/src/QmlControls/ToolStrip.qml @@ -29,6 +29,7 @@ Rectangle { property AbstractButton lastClickedButton: null function simulateClick(buttonIndex) { + buttonIndex = buttonIndex + 1 // skip over title toolStripColumn.children[buttonIndex].checked = true toolStripColumn.children[buttonIndex].clicked() } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 9fcbc6eb83df4dfefaf83ee4f36080400ed31119..59b0308b5e13920bb48314d6c7e794e10bb7e17d 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3344,6 +3344,8 @@ void Vehicle::_sendMavCommandAgain() _mavCommandAckTimer.start(); + qCDebug(VehicleLog) << "_sendMavCommandAgain sending" << queuedCommand.command; + mavlink_message_t msg; if (queuedCommand.commandInt) { mavlink_command_int_t cmd; @@ -3449,6 +3451,8 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message) mavlink_command_ack_t ack; mavlink_msg_command_ack_decode(&message, &ack); + qCDebug(VehicleLog) << QStringLiteral("_handleCommandAck command(%1) result(%2)").arg(ack.command).arg(ack.result); + if (ack.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES && ack.result != MAV_RESULT_ACCEPTED) { qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities.").arg(ack.result); _handleUnsupportedRequestAutopilotCapabilities(); @@ -3899,7 +3903,8 @@ void Vehicle::_handleADSBVehicle(const mavlink_message_t& message) vehicleInfo.availableFlags = 0; vehicleInfo.location.setLatitude(adsbVehicleMsg.lat / 1e7); - vehicleInfo.location.setLatitude(adsbVehicleMsg.lon / 1e7); + vehicleInfo.location.setLongitude(adsbVehicleMsg.lon / 1e7); + vehicleInfo.availableFlags |= ADSBVehicle::LocationAvailable; vehicleInfo.callsign = adsbVehicleMsg.callsign; vehicleInfo.availableFlags |= ADSBVehicle::CallsignAvailable; diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/VehicleSetup/FirmwareUpgradeController.cc index 788a81b763671e913a4898e811b640e7a0cc0730..ae5ec5d012b428f06f4ff4bbad76e4399c67a5b0 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.cc +++ b/src/VehicleSetup/FirmwareUpgradeController.cc @@ -724,28 +724,39 @@ void FirmwareUpgradeController::setSelectedFirmwareBuildType(FirmwareBuildType_t void FirmwareUpgradeController::_buildAPMFirmwareNames(void) { #if !defined(NO_ARDUPILOT_DIALECT) - qCDebug(FirmwareUpgradeLog) << "_buildAPMFirmwareNames"; - bool chibios = _apmChibiOSSetting->rawValue().toInt() == 0; - FirmwareVehicleType_t vehicleType = static_cast(_apmVehicleTypeSetting->rawValue().toInt()); + bool chibios = _apmChibiOSSetting->rawValue().toInt() == 0; + FirmwareVehicleType_t vehicleType = static_cast(_apmVehicleTypeSetting->rawValue().toInt()); + 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 + + 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(); _apmFirmwareUrls.clear(); QString apmDescriptionSuffix("-BL"); - bool bootloaderMatch = _foundBoardInfo.description().endsWith(apmDescriptionSuffix); + bool bootloaderMatch = boardDescription.endsWith(apmDescriptionSuffix); 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(_foundBoardInfo.description())) { - qCDebug(FirmwareUpgradeLog) << "Bootloader match:" << firmwareInfo.friendlyName << _foundBoardInfo.description() << firmwareInfo.rgBootloaderPortString << firmwareInfo.url << firmwareInfo.vehicleType; + if (firmwareInfo.rgBootloaderPortString.contains(boardDescription)) { + qCDebug(FirmwareUpgradeLog) << "Bootloader match:" << firmwareInfo.friendlyName << boardDescription << firmwareInfo.rgBootloaderPortString << firmwareInfo.url << firmwareInfo.vehicleType; match = true; } } else { - if (firmwareInfo.rgVID.contains(_foundBoardInfo.vendorIdentifier()) && firmwareInfo.rgPID.contains(_foundBoardInfo.productIdentifier())) { - qCDebug(FirmwareUpgradeLog) << "Fallback match:" << firmwareInfo.friendlyName << _foundBoardInfo.vendorIdentifier() << _foundBoardInfo.productIdentifier() << _bootloaderBoardID << firmwareInfo.url << firmwareInfo.vehicleType; + 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; } }