diff --git a/src/AutoPilotPlugins/Common/SetupPage.qml b/src/AutoPilotPlugins/Common/SetupPage.qml index 891b6f1fabfd87ada3fb85548a41f150ca9fce8b..2efdf4bb695a10072ca043f83f465d282496000e 100644 --- a/src/AutoPilotPlugins/Common/SetupPage.qml +++ b/src/AutoPilotPlugins/Common/SetupPage.qml @@ -35,10 +35,12 @@ QGCView { property alias advanced: advancedCheckBox.checked property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + property bool _vehicleIsRover: _activeVehicle ? _activeVehicle.rover : false property bool _vehicleArmed: _activeVehicle ? _activeVehicle.armed : false property bool _vehicleFlying: _activeVehicle ? _activeVehicle.flying : false property bool _disableDueToArmed: vehicleComponent ? (!vehicleComponent.allowSetupWhileArmed && _vehicleArmed) : false - property bool _disableDueToFlying: vehicleComponent ? (!vehicleComponent.allowSetupWhileFlying && _vehicleFlying) : false + // FIXME: The _vehicleIsRover checkl is a hack to work around https://github.com/PX4/Firmware/issues/10969 + property bool _disableDueToFlying: vehicleComponent ? (!_vehicleIsRover && !vehicleComponent.allowSetupWhileFlying && _vehicleFlying) : false property string _disableReason: _disableDueToArmed ? qsTr("armed") : qsTr("flying") property real _margins: ScreenTools.defaultFontPixelHeight * 0.5 diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml index a69aff95ebc4f76aebc52cec2935574ccb74b4bf..43387450579bc2bc5634e1e2279f8c939dedf892 100644 --- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml @@ -188,6 +188,15 @@ feed-through of RC AUX1 channel feed-through of RC AUX2 channel + + Copter + Beat Kueng <beat-kueng@gmx.net> + Quadrotor H + motor 1 + motor 2 + motor 3 + motor 4 + diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index 27fb9bd2eca5dd9a974b71af438de2374c4346e7..5823d8ef4c8b20ab041ee3de06b919bdff95a45d 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -245,7 +245,7 @@ QGCCameraControl::photoStatus() QString QGCCameraControl::storageFreeStr() { - return QGCMapEngine::bigSizeToString(static_cast(_storageFree * 1024 * 1024)); + return QGCMapEngine::bigSizeToString(static_cast(_storageFree) * 1024 * 1024); } //----------------------------------------------------------------------------- diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index 6b157e2e228c952b640418c2454abeb28ba9d8ff..f9f74decf7092dc5cad49cd8cc015cc3c36209ac 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -199,7 +199,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString if (!_waitingReadParamIndexMap[componentId].contains(parameterId) && !_waitingReadParamNameMap[componentId].contains(parameterName) && !_waitingWriteParamNameMap[componentId].contains(parameterName)) { - qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Unrequested param update" << parameterName; + qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "Unrequested param update" << parameterName; } // Remove this parameter from the waiting lists @@ -252,14 +252,14 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString if (totalWaitingParamCount) { // More params to wait for, restart timer _waitingParamTimeoutTimer.start(); - qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount; + qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer: totalWaitingParamCount:" << totalWaitingParamCount; } else { if (!_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) { // Still waiting for parameters from default component - qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer (still waiting for default component params)"; + qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer (still waiting for default component params)"; _waitingParamTimeoutTimer.start(); } else { - qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)"; + qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(-1) << "Not restarting _waitingParamTimeoutTimer (all requests satisfied)"; } } @@ -440,7 +440,7 @@ void ParameterManager::refreshAllParameters(uint8_t componentId) _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); QString what = (componentId == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentId); - qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Request to refresh all parameters for component ID:" << what; + qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Request to refresh all parameters for component ID:" << what; } /// Translates FactSystem::defaultComponentId to real component id if needed @@ -449,7 +449,7 @@ int ParameterManager::_actualComponentId(int componentId) if (componentId == FactSystem::defaultComponentId) { componentId = _vehicle->defaultComponentId(); if (componentId == FactSystem::defaultComponentId) { - qWarning() << _logVehiclePrefix() << "Default component id not set"; + qWarning() << _logVehiclePrefix(-1) << "Default component id not set"; } } @@ -564,8 +564,8 @@ bool ParameterManager::_fillIndexBatchQueue(bool waitingParamTimeout) for(int componentId: _waitingReadParamIndexMap.keys()) { if (_waitingReadParamIndexMap[componentId].count()) { - qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count(); - qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix() << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId]; + qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap count" << _waitingReadParamIndexMap[componentId].count(); + qCDebug(ParameterManagerVerbose1Log) << _logVehiclePrefix(componentId) << "_waitingReadParamIndexMap" << _waitingReadParamIndexMap[componentId]; } for(int paramIndex: _waitingReadParamIndexMap[componentId].keys()) { @@ -606,7 +606,7 @@ void ParameterManager::_waitingParamTimeout(void) const int maxBatchSize = 10; int batchCount = 0; - qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_waitingParamTimeout"; + qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "_waitingParamTimeout"; // Now that we have timed out for possibly the first time we can activate the index batch queue _indexBatchQueueActive = true; @@ -617,7 +617,7 @@ void ParameterManager::_waitingParamTimeout(void) if (!paramsRequested && !_waitingForDefaultComponent && !_mapParameterName2Variant.contains(_vehicle->defaultComponentId())) { // Initial load is complete but we still don't have any default component params. Wait one more cycle to see if the // any show up. - qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->defaultComponentId() << _mapParameterName2Variant.keys(); + qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - still don't have default component params" << _vehicle->defaultComponentId() << _mapParameterName2Variant.keys(); _waitingParamTimeoutTimer.start(); _waitingForDefaultComponent = true; return; @@ -672,7 +672,7 @@ void ParameterManager::_waitingParamTimeout(void) Out: if (paramsRequested) { - qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Restarting _waitingParamTimeoutTimer - re-request"; + qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Restarting _waitingParamTimeoutTimer - re-request"; _waitingParamTimeoutTimer.start(); } } @@ -1121,7 +1121,7 @@ void ParameterManager::_checkInitialLoadComplete(void) } _debugCacheCRC.clear(); - qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Initial load complete"; + qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Initial load complete"; // Check for index based load failures QString indexList; @@ -1131,7 +1131,7 @@ void ParameterManager::_checkInitialLoadComplete(void) if (initialLoadFailures) { indexList += ", "; } - indexList += QString("%1").arg(paramIndex); + indexList += QString("%1:%2").arg(componentId).arg(paramIndex); initialLoadFailures = true; qCDebug(ParameterManagerLog) << _logVehiclePrefix(componentId) << "Gave up on initial load after max retries (paramIndex:" << paramIndex << ")"; } @@ -1147,7 +1147,7 @@ void ParameterManager::_checkInitialLoadComplete(void) qCDebug(ParameterManagerLog) << errorMsg; qgcApp()->showMessage(errorMsg); if (!qgcApp()->runningUnitTests()) { - qCWarning(ParameterManagerLog) << _logVehiclePrefix() << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList; + qCWarning(ParameterManagerLog) << _logVehiclePrefix(-1) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList; } } @@ -1161,7 +1161,7 @@ void ParameterManager::_checkInitialLoadComplete(void) void ParameterManager::_initialRequestTimeout(void) { if (!_disableAllRetries && ++_initialRequestRetryCount <= _maxInitialRequestListRetry) { - qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Retrying initial parameter request list"; + qCDebug(ParameterManagerLog) << _logVehiclePrefix(-1) << "Retrying initial parameter request list"; refreshAllParameters(); _initialRequestTimeoutTimer.start(); } else { diff --git a/src/FactSystem/ParameterManager.h b/src/FactSystem/ParameterManager.h index 75479924dd4b04ea4e92b9747f6cfd32d09cfc3e..d9588557054a7461b12ed844e1feb3bab9628261 100644 --- a/src/FactSystem/ParameterManager.h +++ b/src/FactSystem/ParameterManager.h @@ -140,7 +140,7 @@ private: void _addMetaDataToDefaultComponent(void); QString _remapParamNameToVersion(const QString& paramName); void _loadOfflineEditingParams(void); - QString _logVehiclePrefix(int componentId = -1); + QString _logVehiclePrefix(int componentId); void _setLoadProgress(double loadProgress); bool _fillIndexBatchQueue(bool waitingParamTimeout); diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 3cf164b010c35fa78c377f826e16b3e99929f929..c8c9a76aba56a7a67bdda618158a589f5cdb340f 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -462,8 +462,8 @@ void APMFirmwarePlugin::_handleIncomingHeartbeat(Vehicle* vehicle, mavlink_messa bool APMFirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) { - //-- Don't process messages to/from UDP Bridge. It doesn't suffer from these issues - if (message->compid == MAV_COMP_ID_UDP_BRIDGE) { + // Only translate messages which come from the autopilot. All other components are expected to follow current mavlink spec. + if (message->compid != MAV_COMP_ID_AUTOPILOT1) { return true; } diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 0f9fb96221d47bff922b383308aeed970d734b8f..66dcb0828a294d2e86bf5a5eaefab26e3c6d7057 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -3645,6 +3645,11 @@ Used to calculate increased terrain random walk nosie due to movementThe mavlink hearbeat message will not be forwarded if this parameter is set to 'disabled'. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit. + + Activate ODOMETRY loopback + If set, it gets the data from 'vehicle_visual_odometry' instead of 'vehicle_odometry' serving as a loopback of the received ODOMETRY messages on the Mavlink receiver. + + MAVLink protocol version @@ -4151,8 +4156,12 @@ default 1.5 turns per second Multicopter air-mode - The air-mode enables the mixer to increase the total thrust of the multirotor in order to keep attitude and rate control even at low and high throttle. This function should be disabled during tuning as it will help the controller to diverge if the closed-loop is unstable. - + The air-mode enables the mixer to increase the total thrust of the multirotor in order to keep attitude and rate control even at low and high throttle. This function should be disabled during tuning as it will help the controller to diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet). Enabling air-mode for yaw requires the use of an arming switch. + + Disabled + Roll/Pitch + Roll/Pitch/Yaw + Battery power level scaler diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 5aa0bb9bba328edcae4b8a1ac0939ac55cd3a1be..534ef45f1f050feadf9efd1bd605606e430cfa20 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -89,6 +89,7 @@ #include "FactValueSliderListModel.h" #include "ShapeFileHelper.h" #include "QGCFileDownload.h" +#include "FirmwareImage.h" #ifndef NO_SERIAL_LINK #include "SerialLink.h" @@ -236,11 +237,13 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) // Parse command line options bool fClearSettingsOptions = false; // Clear stored settings + bool fClearCache = false; // Clear parameter/airframe caches bool logging = false; // Turn on logging QString loggingOptions; CmdLineOpt_t rgCmdLineOptions[] = { { "--clear-settings", &fClearSettingsOptions, nullptr }, + { "--clear-cache", &fClearCache, nullptr }, { "--logging", &logging, &loggingOptions }, { "--fake-mobile", &_fakeMobile, nullptr }, { "--log-output", &_logOutput, nullptr }, @@ -309,6 +312,15 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) } settings.setValue(_settingsVersionKey, QGC_SETTINGS_VERSION); + if (fClearCache) { + QDir dir(ParameterManager::parameterCacheDir()); + dir.removeRecursively(); + QFile airframe(cachedAirframeMetaDataFile()); + airframe.remove(); + QFile parameter(cachedParameterMetaDataFile()); + parameter.remove(); + } + // Set up our logging filters QGCLoggingCategoryRegister::instance()->setFilterRulesFromSettings(loggingOptions); @@ -839,3 +851,16 @@ void QGCApplication::_gpsNumSatellites(int numSatellites) _gpsRtkFactGroup->numSatellites()->setRawValue(numSatellites); } +QString QGCApplication::cachedParameterMetaDataFile(void) +{ + QSettings settings; + QDir parameterDir = QFileInfo(settings.fileName()).dir(); + return parameterDir.filePath(QStringLiteral("ParameterFactMetaData.xml")); +} + +QString QGCApplication::cachedAirframeMetaDataFile(void) +{ + QSettings settings; + QDir airframeDir = QFileInfo(settings.fileName()).dir(); + return airframeDir.filePath(QStringLiteral("PX4AirframeFactMetaData.xml")); +} diff --git a/src/QGCApplication.h b/src/QGCApplication.h index fa83c39b64c670bd99e84bca18a03eacf08e6313..052bf53f0318631472ad16f285f3992b815070f6 100644 --- a/src/QGCApplication.h +++ b/src/QGCApplication.h @@ -98,6 +98,9 @@ public: FactGroup* gpsRtkFactGroup(void) { return _gpsRtkFactGroup; } + static QString cachedParameterMetaDataFile(void); + static QString cachedAirframeMetaDataFile(void); + public slots: /// You can connect to this slot to show an information message box from a different thread. void informationMessageBoxOnMainThread(const QString& title, const QString& msg); diff --git a/src/VehicleSetup/FirmwareImage.cc b/src/VehicleSetup/FirmwareImage.cc index 6306eceb2e14643ac5c5aa3fddc51a98423bb6bc..95145a93c96eb5d60c923b08e44e44c86ae44930 100644 --- a/src/VehicleSetup/FirmwareImage.cc +++ b/src/VehicleSetup/FirmwareImage.cc @@ -275,12 +275,8 @@ bool FirmwareImage::_px4Load(const QString& imageFilename) _jsonParamXmlKey, // key which holds compressed bytes decompressedBytes); // Returned decompressed bytes if (success) { - // Use settings location as our work directory, this way is something goes wrong the file is still there - // sitting next to the cache files. - QSettings settings; - QDir parameterDir = QFileInfo(settings.fileName()).dir(); - QString parameterFilename = parameterDir.filePath("ParameterFactMetaData.xml"); - QFile parameterFile(parameterFilename); + QString parameterFilename = QGCApplication::cachedParameterMetaDataFile(); + QFile parameterFile(QGCApplication::cachedParameterMetaDataFile()); if (parameterFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) { qint64 bytesWritten = parameterFile.write(decompressedBytes); @@ -306,12 +302,9 @@ bool FirmwareImage::_px4Load(const QString& imageFilename) _jsonAirframeXmlKey, // key which holds compressed bytes decompressedBytes); // Returned decompressed bytes if (success) { - // We cache the airframe xml in the same location as settings and parameters - QSettings settings; - QDir airframeDir = QFileInfo(settings.fileName()).dir(); - QString airframeFilename = airframeDir.filePath("PX4AirframeFactMetaData.xml"); + QString airframeFilename = QGCApplication::cachedAirframeMetaDataFile(); //qDebug() << airframeFilename; - QFile airframeFile(airframeFilename); + QFile airframeFile(QGCApplication::cachedAirframeMetaDataFile()); if (airframeFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) { qint64 bytesWritten = airframeFile.write(decompressedBytes); diff --git a/src/ViewWidgets/CustomCommandWidget.qml b/src/ViewWidgets/CustomCommandWidget.qml index 4d4ee60d7688183ba315e772a6f0d9792cafd4d4..fae5abf1471777da76df5df2618860ff95f128ff 100644 --- a/src/ViewWidgets/CustomCommandWidget.qml +++ b/src/ViewWidgets/CustomCommandWidget.qml @@ -34,7 +34,7 @@ QGCView { "So make sure to test your changes thoroughly before using them in flight.

" + "

Click 'Load Custom Qml file' to provide your custom qml file.

" + "

Click 'Reset' to reset to none.

" + - "

Example usage: https://dev.qgroundcontrol.com/en/tools/custom_command_widget.html

" + "

Example usage: https://docs.qgroundcontrol.com/en/app_menu/custom_command_widget.html

" QGCPalette { id: qgcPal; colorGroupEnabled: enabled }