From 84a985224d88dbdaec583f3378fbbe2b57932059 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Tue, 25 Jul 2023 21:20:11 +0000 Subject: [PATCH 001/118] Update PX4 Firmware metadata Tue Jul 25 21:20:11 UTC 2023 --- .../PX4/PX4ParameterFactMetaData.xml | 39 +++++++++++++++---- 1 file changed, 32 insertions(+), 7 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 9c7a14c6d31..2db8576e93f 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -1307,8 +1307,9 @@ Horizontal position error threshold - This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous position error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). - 0 + This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous position error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). Set to -1 to disable. + -1 + 400 m 1 @@ -1316,6 +1317,7 @@ EPH threshold for RTL Specify the threshold for triggering a warning for low local position accuracy. Additionally triggers a RTL if currently in Mission or Loiter mode. Local position has to be still declared valid, which is most of all depending on COM_POS_FS_EPH. Use this feature on systems with dead-reckoning capabilites (e.g. fixed-wing vehicles with airspeed sensor) to improve the user notification and failure mitigation when flying in GNSS-denied areas. Set to -1 to disable. -1 + 1000 m @@ -2045,9 +2047,32 @@ gauss/s 6 - + Magnetic field strength test selection - When set, the EKF checks the strength of the magnetic field to decide whether the magnetometer data is valid. If GPS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. + Bitmask to set which check is used to decide whether the magnetometer data is valid. If GNSS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find the theoretical strength and inclination using the WMM + 0 + 7 + + Strength (EKF2_MAG_CHK_STR) + Inclination (EKF2_MAG_CHK_INC) + Wait for WMM + + + + Magnetic field inclination check tolerance + Maximum allowed deviation from the expected magnetic field inclination to pass the check. + 0.0 + 90.0 + deg + 1 + + + Magnetic field strength check tolerance + Maximum allowed deviation from the expected magnetic field strength to pass the check. + 0.0 + 1.0 + gauss + 2 Magnetic declination @@ -3848,9 +3873,9 @@ m 1 - - Use Pre-emptive geofence triggering - Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory would result in a breach happening before the vehicle can make evasive maneuvers. The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing). + + [EXPERIMENTAL] Use Pre-emptive geofence triggering + WARNING: This experimental feature may cause flyaways. Use at your own risk. Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory would result in a breach happening before the vehicle can make evasive maneuvers. The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing). Geofence source From 1130ab3ba49fe3fd85f1cba6a2f237e73e0208f7 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Thu, 27 Jul 2023 14:30:37 +0000 Subject: [PATCH 002/118] Update PX4 Firmware metadata Thu Jul 27 14:30:37 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 2db8576e93f..346705c07bf 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -1252,8 +1252,8 @@ - Enable Motor Testing - If set, enables the motor test interface via MAVLink (DO_MOTOR_TEST), that allows spinning the motors for testing purposes. + Enable Actuator Testing + If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that allows spinning the motors and moving the servos for testing purposes. Time-out to wait when onboard computer connection is lost before warning about loss connection From a07c4c257db1147e2eaa24608304642870cabcdf Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Thu, 27 Jul 2023 01:11:55 +0200 Subject: [PATCH 003/118] ToolStrip.qml: Fix Flickable height, it was bigger than panel --- src/QmlControls/ToolStrip.qml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/QmlControls/ToolStrip.qml b/src/QmlControls/ToolStrip.qml index da9083937b5..ad5602c5da4 100644 --- a/src/QmlControls/ToolStrip.qml +++ b/src/QmlControls/ToolStrip.qml @@ -52,7 +52,7 @@ Rectangle { anchors.top: parent.top anchors.left: parent.left anchors.right: parent.right - height: parent.height + height: parent.height - anchors.margins * 2 contentHeight: toolStripColumn.height flickableDirection: Flickable.VerticalFlick clip: true From fa9bf8a00fb064a8f4f9770894e1e019a581f72a Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sat, 29 Jul 2023 14:24:48 -0700 Subject: [PATCH 004/118] Allow app data to save to sd card on android --- android.pri | 9 ++++++ android/src/AndroidInterface.cc | 21 ++++++++++++ android/src/AndroidInterface.h | 21 ++++++++++++ .../mavlink/qgroundcontrol/QGCActivity.java | 32 +++++++++++++++++++ src/Settings/App.SettingsGroup.json | 10 +++++- src/Settings/AppSettings.cc | 27 ++++++++++++++-- src/Settings/AppSettings.h | 1 + src/api/QGCCorePlugin.cc | 7 ++++ src/ui/preferences/GeneralSettings.qml | 9 ++++-- 9 files changed, 131 insertions(+), 6 deletions(-) create mode 100644 android/src/AndroidInterface.cc create mode 100644 android/src/AndroidInterface.h diff --git a/android.pri b/android.pri index 3962196ca46..a0397a68a1f 100644 --- a/android.pri +++ b/android.pri @@ -53,3 +53,12 @@ DISTFILES += \ $$PWD/android/build.gradle \ $$PWD/android/gradle/wrapper/gradle-wrapper.properties \ $$PWD/android/gradlew.bat + +SOURCES += \ + $$PWD/android/src/AndroidInterface.cc + +HEADERS += \ + $$PWD/android/src/AndroidInterface.h + +INCLUDEPATH += \ + $$PWD/android/src diff --git a/android/src/AndroidInterface.cc b/android/src/AndroidInterface.cc new file mode 100644 index 00000000000..87b2441d1a4 --- /dev/null +++ b/android/src/AndroidInterface.cc @@ -0,0 +1,21 @@ +/**************************************************************************** + * + * Copyright (C) 2018 Pinecone Inc. All rights reserved. + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include +#include +#include "QGCApplication.h" +#include "AndroidInterface.h" +#include + +QString AndroidInterface::getSDCardPath() +{ + QAndroidJniObject value = QAndroidJniObject::callStaticObjectMethod("org/mavlink/qgroundcontrol/QGCActivity", "getSDCardPath", + "()Ljava/lang/String;"); + return value.toString(); +} diff --git a/android/src/AndroidInterface.h b/android/src/AndroidInterface.h new file mode 100644 index 00000000000..a03370a1983 --- /dev/null +++ b/android/src/AndroidInterface.h @@ -0,0 +1,21 @@ +/**************************************************************************** + * + * Copyright (C) 2018 Pinecone Inc. All rights reserved. + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +#include +#include +#include +#include + +class AndroidInterface +{ +public: + static QString getSDCardPath(); +}; diff --git a/android/src/org/mavlink/qgroundcontrol/QGCActivity.java b/android/src/org/mavlink/qgroundcontrol/QGCActivity.java index 14fb760c2d9..c46192ba951 100644 --- a/android/src/org/mavlink/qgroundcontrol/QGCActivity.java +++ b/android/src/org/mavlink/qgroundcontrol/QGCActivity.java @@ -38,6 +38,7 @@ import java.util.Timer; import java.util.TimerTask; import java.io.IOException; +import java.lang.reflect.Method; import android.app.Activity; import android.app.PendingIntent; @@ -58,6 +59,8 @@ import android.view.WindowManager; import android.os.Bundle; import android.bluetooth.BluetoothDevice; +import android.os.storage.StorageManager; +import android.os.storage.StorageVolume; import com.hoho.android.usbserial.driver.*; import org.qtproject.qt5.android.bindings.QtActivity; @@ -762,5 +765,34 @@ public void run() { } }).start(); } + + public static String getSDCardPath() { + StorageManager storageManager = (StorageManager)_instance.getSystemService(Activity.STORAGE_SERVICE); + List volumes = storageManager.getStorageVolumes(); + Method mMethodGetPath; + String path = ""; + for (StorageVolume vol : volumes) { + try { + mMethodGetPath = vol.getClass().getMethod("getPath"); + } catch (NoSuchMethodException e) { + e.printStackTrace(); + continue; + } + try { + path = (String) mMethodGetPath.invoke(vol); + } catch (Exception e) { + e.printStackTrace(); + continue; + } + + if (vol.isRemovable() == true) { + Log.i(TAG, "removable sd card mounted " + path); + return path; + } else { + Log.i(TAG, "storage mounted " + path); + } + } + return ""; + } } diff --git a/src/Settings/App.SettingsGroup.json b/src/Settings/App.SettingsGroup.json index 8682532c917..fe58bb396e9 100644 --- a/src/Settings/App.SettingsGroup.json +++ b/src/Settings/App.SettingsGroup.json @@ -174,10 +174,18 @@ { "name": "savePath", "shortDesc": "Application save directory", - "longDesc": "Directory to which all data files are saved/loaded from", + "longDesc": "Directory to which all data files are saved/loaded from", "type": "string", "default": "" }, +{ + "name": "androidSaveToSDCard", + "shortDesc": "Save to SD card", + "longDesc": "Application data is saved to the sd card", + "type": "bool", + "default": false, + "qgcRebootRequired": true +}, { "name": "userBrandImageIndoor", "shortDesc": "User-selected brand image", diff --git a/src/Settings/AppSettings.cc b/src/Settings/AppSettings.cc index 2324783ee34..6da065251aa 100644 --- a/src/Settings/AppSettings.cc +++ b/src/Settings/AppSettings.cc @@ -12,6 +12,10 @@ #include "QGCApplication.h" #include "ParameterManager.h" +#ifdef __android__ +#include "AndroidInterface.h" +#endif + #include #include #include @@ -95,10 +99,26 @@ DECLARE_SETTINGGROUP(App, "") QDir rootDir = QDir(QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation)); savePathFact->setRawValue(rootDir.absolutePath()); #else - QDir rootDir = QDir(QStandardPaths::writableLocation(QStandardPaths::GenericDataLocation)); - savePathFact->setRawValue(rootDir.filePath(appName)); + QString rootDirPath; + #ifdef __android__ + if (androidSaveToSDCard()->rawValue().toBool()) { + rootDirPath = AndroidInterface::getSDCardPath(); + qDebug() << "AndroidInterface::getSDCardPath();" << rootDirPath; + if (rootDirPath.isEmpty() || !QDir(rootDirPath).exists()) { + rootDirPath.clear(); + qgcApp()->showAppMessage(tr("Save to SD card specified for application data. But no SD card present. Using internal storage.")); + } else if (!QFileInfo(rootDirPath).isWritable()) { + rootDirPath.clear(); + qgcApp()->showAppMessage(tr("Save to SD card specified for application data. But SD card is write protected. Using internal storage.")); + } + } + #endif + if (rootDirPath.isEmpty()) { + rootDirPath = QStandardPaths::writableLocation(QStandardPaths::GenericDataLocation); + } + savePathFact->setRawValue(QDir(rootDirPath).filePath(appName)); #endif - savePathFact->setVisible(false); + savePathFact->setVisible(false); #else QDir rootDir = QDir(QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation)); savePathFact->setRawValue(rootDir.filePath(appName)); @@ -128,6 +148,7 @@ DECLARE_SETTINGSFACT(AppSettings, virtualJoystickAutoCenterThrottle) DECLARE_SETTINGSFACT(AppSettings, appFontPointSize) DECLARE_SETTINGSFACT(AppSettings, showLargeCompass) DECLARE_SETTINGSFACT(AppSettings, savePath) +DECLARE_SETTINGSFACT(AppSettings, androidSaveToSDCard) DECLARE_SETTINGSFACT(AppSettings, useChecklist) DECLARE_SETTINGSFACT(AppSettings, enforceChecklist) DECLARE_SETTINGSFACT(AppSettings, mapboxToken) diff --git a/src/Settings/AppSettings.h b/src/Settings/AppSettings.h index ee7e618eea7..c2e190199b5 100644 --- a/src/Settings/AppSettings.h +++ b/src/Settings/AppSettings.h @@ -44,6 +44,7 @@ class AppSettings : public SettingsGroup DEFINE_SETTINGFACT(indoorPalette) DEFINE_SETTINGFACT(showLargeCompass) DEFINE_SETTINGFACT(savePath) + DEFINE_SETTINGFACT(androidSaveToSDCard) DEFINE_SETTINGFACT(useChecklist) DEFINE_SETTINGFACT(enforceChecklist) DEFINE_SETTINGFACT(mapboxToken) diff --git a/src/api/QGCCorePlugin.cc b/src/api/QGCCorePlugin.cc index 45db47bf7fe..318c7a9a89b 100644 --- a/src/api/QGCCorePlugin.cc +++ b/src/api/QGCCorePlugin.cc @@ -248,6 +248,13 @@ bool QGCCorePlugin::adjustSettingMetaData(const QString& settingsGroup, FactMeta return true; } #endif + +#ifndef __android__ + if (metaData.name() == AppSettings::androidSaveToSDCardName) { + // This only shows on android builds + return false; + } +#endif } return true; // Show setting in ui diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index f006759a10e..1b9b9d68f20 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -685,6 +685,13 @@ Rectangle { property Fact _audioMuted: QGroundControl.settingsManager.appSettings.audioMuted } + FactCheckBox { + text: qsTr("Save application data to SD Card") + fact: _androidSaveToSDCard + visible: _androidSaveToSDCard.visible + property Fact _androidSaveToSDCard: QGroundControl.settingsManager.appSettings.androidSaveToSDCard + } + FactCheckBox { text: qsTr("Check for Internet connection") fact: _checkInternet @@ -727,8 +734,6 @@ Rectangle { } } - //----------------------------------------------------------------- - //-- Save path RowLayout { id: pathRow anchors.margins: _margins From 4003b48c5d1d72a2e5f285966e2381b8c9527de5 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 31 Jul 2023 13:33:03 -0700 Subject: [PATCH 005/118] Fix sd card permission --- android/AndroidManifest.xml | 1 + android/src/AndroidInterface.cc | 17 ++++++++++++++++- 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/android/AndroidManifest.xml b/android/AndroidManifest.xml index bcd9c8f872d..5cbe6cd8352 100644 --- a/android/AndroidManifest.xml +++ b/android/AndroidManifest.xml @@ -102,5 +102,6 @@ + diff --git a/android/src/AndroidInterface.cc b/android/src/AndroidInterface.cc index 87b2441d1a4..cd8afdc369b 100644 --- a/android/src/AndroidInterface.cc +++ b/android/src/AndroidInterface.cc @@ -12,10 +12,25 @@ #include "QGCApplication.h" #include "AndroidInterface.h" #include +#include QString AndroidInterface::getSDCardPath() { QAndroidJniObject value = QAndroidJniObject::callStaticObjectMethod("org/mavlink/qgroundcontrol/QGCActivity", "getSDCardPath", "()Ljava/lang/String;"); - return value.toString(); + QString sdCardPath = value.toString(); + + QString readPermission("android.permission.READ_EXTERNAL_STORAGE"); + QString writePermission("android.permission.WRITE_EXTERNAL_STORAGE"); + + if (QtAndroid::checkPermission(readPermission) == QtAndroid::PermissionResult::Denied || + QtAndroid::checkPermission(writePermission) == QtAndroid::PermissionResult::Denied) { + QtAndroid::PermissionResultMap resultHash = QtAndroid::requestPermissionsSync(QStringList({ readPermission, writePermission })); + if (resultHash[readPermission] == QtAndroid::PermissionResult::Denied || + resultHash[writePermission] == QtAndroid::PermissionResult::Denied) { + return QString(); + } + } + + return sdCardPath; } From 27341c833539f926cbe6c2aea3aebf86b8a3dcad Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Fri, 4 Aug 2023 15:21:33 +0000 Subject: [PATCH 006/118] Update PX4 Firmware metadata Fri Aug 4 15:21:33 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 346705c07bf..313fc31b223 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -2110,14 +2110,11 @@ Type of magnetometer fusion - Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight with fallback to magnetic heading fusion if there is insufficient motion to make yaw or magnetic field states observable. If set to 'Magnetic heading' magnetic heading fusion is used at all times. If set to '3-axis' 3-axis field fusion is used at all times. If set to 'VTOL custom' the behaviour is the same as 'Automatic', but if fusing airspeed, magnetometer fusion is only allowed to modify the magnetic field states. This can be used by VTOL platforms with large magnetic field disturbances to prevent incorrect bias states being learned during forward flight operation which can adversely affect estimation accuracy after transition to hovering flight. If set to 'MC custom' the behaviour is the same as 'Automatic, but if there are no earth frame position or velocity observations being used, the magnetometer will not be used. This enables vehicles to operate with no GPS in environments where the magnetic field cannot be used to provide a heading reference. Prior to flight, the yaw angle is assumed to be constant if movement tests indicate that the vehicle is static. This allows the vehicle to be placed on the ground to learn the yaw gyro bias prior to flight. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality). + Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight with fallback to magnetic heading fusion if there is insufficient motion to make yaw or magnetic field states observable. If set to 'Magnetic heading' magnetic heading fusion is used at all times. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality). true Automatic Magnetic heading - 3-axis - VTOL custom - MC custom None From 9b6b35992810cfc788b05282865fd4286db94eb5 Mon Sep 17 00:00:00 2001 From: Junwoo Hwang Date: Fri, 4 Aug 2023 17:10:50 +0200 Subject: [PATCH 007/118] PX4SimpleFlightModes.qml: Rename the variable for bugfix This was introduced in https://github.com/mavlink/qgroundcontrol/commit/d5dc4f1af17151d7e7f88372847bc12ac499ccb9, and the refactor didn't fix the case for RC_MAP_FLAPS case correctly, leading to the bug report: https://github.com/PX4/PX4-Autopilot/issues/21927 --- src/AutoPilotPlugins/PX4/PX4SimpleFlightModes.qml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/AutoPilotPlugins/PX4/PX4SimpleFlightModes.qml b/src/AutoPilotPlugins/PX4/PX4SimpleFlightModes.qml index 5b9cdd9abe9..26e7901cd52 100644 --- a/src/AutoPilotPlugins/PX4/PX4SimpleFlightModes.qml +++ b/src/AutoPilotPlugins/PX4/PX4SimpleFlightModes.qml @@ -34,8 +34,8 @@ Item { _switchTHList.push("RC_TRANS_TH") } if (controller.vehicle.fixedWing) { - _switchFactList.push("RC_MAP_FLAPS") - _switchTHFactList.push("") + _switchNameList.push("RC_MAP_FLAPS") + _switchTHList.push("") } switchRepeater.model = _switchNameList } From 48d1441493b3c193bbd2c5fc63c650bf2ae51e48 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 7 Aug 2023 12:30:43 -0700 Subject: [PATCH 008/118] Support custom builds with joysticks which are buttons only For example a Herelink controller custom build will use this. --- src/Joystick/Joystick.cc | 14 +++++++++----- src/Joystick/Joystick.h | 5 +++++ src/VehicleSetup/JoystickConfig.qml | 12 +++++++++++- src/VehicleSetup/SetupView.qml | 2 +- src/api/QGCOptions.h | 4 ++++ 5 files changed, 30 insertions(+), 7 deletions(-) diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index 767d2081812..670cc777e3f 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -16,6 +16,8 @@ #include "VideoManager.h" #include "QGCCameraManager.h" #include "QGCCameraControl.h" +#include "QGCCorePlugin.h" +#include "QGCOptions.h" #include @@ -108,6 +110,8 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC , _totalButtonCount(_buttonCount+_hatButtonCount) , _multiVehicleManager(multiVehicleManager) { + _useButtonsOnly = qgcApp()->toolbox()->corePlugin()->options()->joystickUseButtonsOnly(); + qRegisterMetaType(); _rgAxisValues = new int[static_cast(_axisCount)]; @@ -713,10 +717,9 @@ void Joystick::startPolling(Vehicle* vehicle) } // Update qml in case of joystick transition emit calibratedChanged(_calibrated); - // Build action list _buildActionList(vehicle); - // Only connect the new vehicle if it wants joystick data - if (vehicle->joystickEnabled()) { + + if (vehicle->joystickEnabled() || _useButtonsOnly) { _pollingStartedForCalibration = false; connect(this, &Joystick::setArmed, _activeVehicle, &Vehicle::setArmedShowError); connect(this, &Joystick::setVtolInFwdFlight, _activeVehicle, &Vehicle::setVtolInFwdFlight); @@ -738,7 +741,7 @@ void Joystick::startPolling(Vehicle* vehicle) void Joystick::stopPolling(void) { if (isRunning()) { - if (_activeVehicle && _activeVehicle->joystickEnabled()) { + if (_activeVehicle && (_activeVehicle->joystickEnabled() || _useButtonsOnly)) { disconnect(this, &Joystick::setArmed, _activeVehicle, &Vehicle::setArmedShowError); disconnect(this, &Joystick::setVtolInFwdFlight, _activeVehicle, &Vehicle::setVtolInFwdFlight); disconnect(this, &Joystick::setFlightMode, _activeVehicle, &Vehicle::setFlightMode); @@ -985,9 +988,10 @@ void Joystick::setCalibrationMode(bool calibrating) void Joystick::_executeButtonAction(const QString& action, bool buttonDown) { - if (!_activeVehicle || !_activeVehicle->joystickEnabled() || action == _buttonActionNone) { + if (!_activeVehicle || (!_activeVehicle->joystickEnabled() && !_useButtonsOnly) || action == _buttonActionNone) { return; } + if (action == _buttonActionArm) { if (buttonDown) emit setArmed(true); } else if (action == _buttonActionDisarm) { diff --git a/src/Joystick/Joystick.h b/src/Joystick/Joystick.h index fcdc5bf8d82..7da35114712 100644 --- a/src/Joystick/Joystick.h +++ b/src/Joystick/Joystick.h @@ -94,6 +94,10 @@ class Joystick : public QThread Q_PROPERTY(int axisCount READ axisCount CONSTANT) Q_PROPERTY(bool requiresCalibration READ requiresCalibration CONSTANT) + // This property is used to indicate a joystick setup where the stick axes are ignored and only the + // buttons are supported. This type of setup is used by a Herelink controller for example. + Q_PROPERTY(bool useButtonsOnly MEMBER _useButtonsOnly CONSTANT) + //-- Actions assigned to buttons Q_PROPERTY(QStringList buttonActions READ buttonActions NOTIFY buttonActionsChanged) @@ -275,6 +279,7 @@ class Joystick : public QThread std::atomic _exitThread{false}; ///< true: signal thread to exit bool _calibrationMode = false; + bool _useButtonsOnly = false; int* _rgAxisValues = nullptr; Calibration_t* _rgCalibration = nullptr; ThrottleMode_t _throttleMode = ThrottleModeDownZero; diff --git a/src/VehicleSetup/JoystickConfig.qml b/src/VehicleSetup/JoystickConfig.qml index 3ba6e90b67e..2c744ab615f 100644 --- a/src/VehicleSetup/JoystickConfig.qml +++ b/src/VehicleSetup/JoystickConfig.qml @@ -62,20 +62,30 @@ SetupPage { id: bar width: parent.width Component.onCompleted: { - currentIndex = _activeJoystick && _activeJoystick.calibrated ? 0 : 2 + currentIndex = 0 + if (_activeJoystick) { + if (_activeJoystick.useButtonsOnly) { + currentIndex = 1 + } else if (_activeJoystick.calibrated) { + currentIndex = 2 + } + } } anchors.top: parent.top QGCTabButton { text: qsTr("General") + visible: !_activeJoystick.useButtonsOnly } QGCTabButton { text: qsTr("Button Assigment") } QGCTabButton { text: qsTr("Calibration") + visible: !_activeJoystick.useButtonsOnly } QGCTabButton { text: qsTr("Advanced") + visible: !_activeJoystick.useButtonsOnly } } diff --git a/src/VehicleSetup/SetupView.qml b/src/VehicleSetup/SetupView.qml index 70946d1edc2..012aebd32ef 100644 --- a/src/VehicleSetup/SetupView.qml +++ b/src/VehicleSetup/SetupView.qml @@ -260,7 +260,7 @@ Rectangle { id: joystickButton imageResource: "/qmlimages/Joystick.png" setupIndicator: true - setupComplete: joystickManager.activeJoystick ? joystickManager.activeJoystick.calibrated : false + setupComplete: joystickManager.activeJoystick ? (joystickManager.activeJoystick.calibrated || joystickManager.activeJoystick.useButtonsOnly) : false exclusiveGroup: setupButtonGroup visible: _fullParameterVehicleAvailable && joystickManager.joysticks.length !== 0 text: qsTr("Joystick") diff --git a/src/api/QGCOptions.h b/src/api/QGCOptions.h index 43f01167d0c..e796dbfb3d0 100644 --- a/src/api/QGCOptions.h +++ b/src/api/QGCOptions.h @@ -146,6 +146,10 @@ class QGCOptions : public QObject virtual QGCFlyViewOptions* flyViewOptions (); + // This is used to indicate a joystick setup where the stick axes are ignored and only the + // buttons are supported. This type of setup is used by a Herelink controller for example. + virtual bool joystickUseButtonsOnly() const { return false; } + signals: void showSensorCalibrationCompassChanged (bool show); void showSensorCalibrationGyroChanged (bool show); From e7ccce4844a37254d6a7eb7a06d015d24fb22e5f Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Tue, 8 Aug 2023 17:55:21 +0000 Subject: [PATCH 009/118] Update PX4 Firmware metadata Tue Aug 8 17:55:21 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 313fc31b223..fb1cee5c4fe 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -505,7 +505,7 @@ - + Acceleration compensation based on GPS velocity From 7b49824ab0e424de0f1ce5429c75a8a4036e903d Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sat, 5 Aug 2023 12:55:35 -0700 Subject: [PATCH 010/118] Remove noisy qmake output --- QGCExternalLibs.pri | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/QGCExternalLibs.pri b/QGCExternalLibs.pri index af13c8693ea..2d3422c66dd 100644 --- a/QGCExternalLibs.pri +++ b/QGCExternalLibs.pri @@ -226,9 +226,9 @@ MacBuild { # Include Android OpenSSL libs AndroidBuild { include($$SOURCE_DIR/libs/OpenSSL/android_openssl/openssl.pri) - message("ANDROID_EXTRA_LIBS") - message($$ANDROID_TARGET_ARCH) - message($$ANDROID_EXTRA_LIBS) + #message("ANDROID_EXTRA_LIBS") + #message($$ANDROID_TARGET_ARCH) + #message($$ANDROID_EXTRA_LIBS) } # Pairing From f9ac752320681555fd56f3d889be994419e25c5b Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sat, 5 Aug 2023 12:57:57 -0700 Subject: [PATCH 011/118] Android support for serial/bluetooth disabling --- QGCCommon.pri | 4 ++++ android.pri | 21 +++++++++++++++++++-- android/AndroidManifest.xml | 13 +++++++------ qgroundcontrol.pro | 5 ++--- 4 files changed, 32 insertions(+), 11 deletions(-) diff --git a/QGCCommon.pri b/QGCCommon.pri index 2679aab1bfe..31ae0f4cda5 100644 --- a/QGCCommon.pri +++ b/QGCCommon.pri @@ -141,6 +141,10 @@ linux|macx|ios { } } +NoSerialBuild { + message("Serial port support disabled") +} + !MacBuild:!AndroidBuild { # See QGCPostLinkCommon.pri for details on why MacBuild doesn't use DESTDIR DESTDIR = staging diff --git a/android.pri b/android.pri index a0397a68a1f..3539bd44035 100644 --- a/android.pri +++ b/android.pri @@ -4,6 +4,9 @@ QT += androidextras ANDROID_PACKAGE_SOURCE_DIR = $$PWD/android +android_source_dir_target.commands = echo Updating Android Manifest +android_source_dir_target.depends = FORCE + exists($$PWD/custom/android) { message("Merging $$PWD/custom/android/ -> $$PWD/android/") @@ -12,11 +15,25 @@ exists($$PWD/custom/android) { PRE_TARGETDEPS += $$android_source_dir_target.target QMAKE_EXTRA_TARGETS += android_source_dir_target - android_source_dir_target.commands = $$QMAKE_MKDIR $$ANDROID_PACKAGE_SOURCE_DIR && \ + android_source_dir_target.commands = $$android_source_dir_target.commands && \ + $$QMAKE_MKDIR $$ANDROID_PACKAGE_SOURCE_DIR && \ $$QMAKE_COPY_DIR $$PWD/android/* $$OUT_PWD/ANDROID_PACKAGE_SOURCE_DIR && \ $$QMAKE_COPY_DIR $$PWD/custom/android/* $$OUT_PWD/ANDROID_PACKAGE_SOURCE_DIR && \ $$QMAKE_STREAM_EDITOR -i \"s/package=\\\"org.mavlink.qgroundcontrol\\\"/package=\\\"$$QGC_ANDROID_PACKAGE\\\"/\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml - android_source_dir_target.depends = FORCE +} + +NoSerialBuild { + # No need to add anything to manifest + android_source_dir_target.commands = $$android_source_dir_target.commands && \ + $$QMAKE_STREAM_EDITOR -i \"s///\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml + android_source_dir_target.commands = $$android_source_dir_target.commands && \ + $$QMAKE_STREAM_EDITOR -i \"s///\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml +} else { + # Updates the manifest for usb device support + android_source_dir_target.commands = $$android_source_dir_target.commands && \ + $$QMAKE_STREAM_EDITOR -i \"s//\r\n\r\n/\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml + android_source_dir_target.commands = $$android_source_dir_target.commands && \ + $$QMAKE_STREAM_EDITOR -i \"s//\r\n\r\n/\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml } exists($$PWD/custom/android/AndroidManifest.xml) { diff --git a/android/AndroidManifest.xml b/android/AndroidManifest.xml index 5cbe6cd8352..63ec9970381 100644 --- a/android/AndroidManifest.xml +++ b/android/AndroidManifest.xml @@ -13,16 +13,17 @@ + + - - - + + - - - + + + diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 27e34fd89c7..f3d7704a173 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -182,13 +182,12 @@ contains (CONFIG, QGC_DISABLE_PX4_PLUGIN_FACTORY) { # Bluetooth contains (DEFINES, QGC_DISABLE_BLUETOOTH) { - message("Skipping support for Bluetooth (manual override from command line)") + message("Bluetooth support disabled (manual override from command line)") DEFINES -= QGC_ENABLE_BLUETOOTH } else:exists(user_config.pri):infile(user_config.pri, DEFINES, QGC_DISABLE_BLUETOOTH) { - message("Skipping support for Bluetooth (manual override from user_config.pri)") + message("Bluetooth support disabled (manual override from user_config.pri)") DEFINES -= QGC_ENABLE_BLUETOOTH } else:exists(user_config.pri):infile(user_config.pri, DEFINES, QGC_ENABLE_BLUETOOTH) { - message("Including support for Bluetooth (manual override from user_config.pri)") DEFINES += QGC_ENABLE_BLUETOOTH } From 67be0d7441fd50a861d1c0c87cbbbe5125eb8de0 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 4 Aug 2023 12:37:10 -0700 Subject: [PATCH 012/118] Fix turning on edit for mobile --- src/FlightDisplay/TelemetryValuesBar.qml | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/FlightDisplay/TelemetryValuesBar.qml b/src/FlightDisplay/TelemetryValuesBar.qml index 670f2ab8a6b..136cfe1756f 100644 --- a/src/FlightDisplay/TelemetryValuesBar.qml +++ b/src/FlightDisplay/TelemetryValuesBar.qml @@ -92,8 +92,17 @@ Rectangle { y: telemetryLayout.y width: telemetryLayout.width height: telemetryLayout.height - hoverEnabled: true + hoverEnabled: !ScreenTools.isMobile propagateComposedEvents: true + + onClicked: { + if (ScreenTools.isMobile && !valueArea.settingsUnlocked) { + valueArea.settingsUnlocked = true + mouse.accepted = true + } else { + mouse.accepted = false + } + } } HorizontalFactValueGrid { From bee8528c2bc0b0b7c87f190c6c83dc389be4cc38 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 4 Aug 2023 14:17:11 -0700 Subject: [PATCH 013/118] Prevent virtual keyboard from popping up on combo box entry --- src/QmlControls/ParameterEditorDialog.qml | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/QmlControls/ParameterEditorDialog.qml b/src/QmlControls/ParameterEditorDialog.qml index 36270507c08..f0bdf7049aa 100644 --- a/src/QmlControls/ParameterEditorDialog.qml +++ b/src/QmlControls/ParameterEditorDialog.qml @@ -38,6 +38,7 @@ QGCPopupDialog { property bool _editingParameter: fact.componentId != 0 property bool _allowForceSave: QGroundControl.corePlugin.showAdvancedUI || !_editingParameter property bool _allowDefaultReset: fact.defaultValueAvailable && (QGroundControl.corePlugin.showAdvancedUI || !_editingParameter) + property bool _showCombo: fact.enumStrings.length !== 0 && fact.bitmaskStrings.length === 0 && !validate ParameterEditorController { id: controller; } @@ -114,11 +115,11 @@ QGCPopupDialog { text: validate ? validateValue : fact.valueString unitsLabel: fact.units showUnits: fact.units != "" - focus: setFocus - inputMethodHints: (fact.typeIsString || ScreenTools.isiOS) ? - Qt.ImhNone : // iOS numeric keyboard has no done button, we can't use it + focus: setFocus && visible + inputMethodHints: (fact.typeIsString || ScreenTools.isiOS) ? // iOS numeric keyboard has no done button, we can't use it + Qt.ImhNone : Qt.ImhFormattedNumbersOnly // Forces use of virtual numeric keyboard - visible: fact.enumStrings.length === 0 || validate || manualEntry.checked + visible: !_showCombo || validate || manualEntry.checked } QGCComboBox { @@ -126,8 +127,7 @@ QGCPopupDialog { width: _editFieldWidth model: fact.enumStrings visible: _showCombo - - property bool _showCombo: fact.enumStrings.length !== 0 && fact.bitmaskStrings.length === 0 && !validate + focus: setFocus && visible Component.onCompleted: { // We can't bind directly to fact.enumIndex since that would add an unknown value From 0695c93fad3fd333f6c708379a5a787f25a490c8 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 4 Aug 2023 15:14:09 -0700 Subject: [PATCH 014/118] Increase touch area border size for better visibility --- src/QmlControls/QGCMouseArea.qml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/QmlControls/QGCMouseArea.qml b/src/QmlControls/QGCMouseArea.qml index e1a9f2c532c..9218c5df017 100644 --- a/src/QmlControls/QGCMouseArea.qml +++ b/src/QmlControls/QGCMouseArea.qml @@ -26,7 +26,7 @@ MouseArea { Rectangle { anchors.fill: parent border.color: "red" - border.width: QGroundControl.corePlugin.showTouchAreas ? 1 : 0 + border.width: QGroundControl.corePlugin.showTouchAreas ? 3 : 0 color: "transparent" } } From ed093aff6b258e2543c6822b6c2fd4adee401200 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 4 Aug 2023 15:14:38 -0700 Subject: [PATCH 015/118] Add showTouchAreas support --- src/QmlControls/QGCToolBarButton.qml | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/src/QmlControls/QGCToolBarButton.qml b/src/QmlControls/QGCToolBarButton.qml index 16380a9adfa..c7903be1dce 100644 --- a/src/QmlControls/QGCToolBarButton.qml +++ b/src/QmlControls/QGCToolBarButton.qml @@ -10,6 +10,7 @@ import QtQuick 2.3 import QtQuick.Controls 2.4 +import QGroundControl 1.0 import QGroundControl.Controls 1.0 import QGroundControl.Palette 1.0 import QGroundControl.ScreenTools 1.0 @@ -31,8 +32,10 @@ Button { onCheckedChanged: checkable = false background: Rectangle { - anchors.fill: parent - color: button.checked ? qgcPal.buttonHighlight : Qt.rgba(0,0,0,0) + anchors.fill: parent + color: button.checked ? qgcPal.buttonHighlight : Qt.rgba(0,0,0,0) + border.color: "red" + border.width: QGroundControl.corePlugin.showTouchAreas ? 3 : 0 } contentItem: Row { From 551fbc079068c273eb47b2e955841434b83cc339 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 4 Aug 2023 15:15:03 -0700 Subject: [PATCH 016/118] Allow easter eggs to work on mobile --- src/ui/MainRootWindow.qml | 27 ++++++++++++++++++++++----- 1 file changed, 22 insertions(+), 5 deletions(-) diff --git a/src/ui/MainRootWindow.qml b/src/ui/MainRootWindow.qml index 5ef22db06cd..70845f1d9bc 100644 --- a/src/ui/MainRootWindow.qml +++ b/src/ui/MainRootWindow.qml @@ -373,23 +373,40 @@ ApplicationWindow { onClicked: { if (mouse.modifiers & Qt.ControlModifier) { QGroundControl.corePlugin.showTouchAreas = !QGroundControl.corePlugin.showTouchAreas - } else if (mouse.modifiers & Qt.ShiftModifier) { + } else if (ScreenTools.isMobile || mouse.modifiers & Qt.ShiftModifier) { if(!QGroundControl.corePlugin.showAdvancedUI) { - advancedModeConfirmation.open() + advancedModeOnConfirmation.open() } else { - QGroundControl.corePlugin.showAdvancedUI = false + advancedModeOffConfirmation.open() } } } + // This allows you to change this on mobile + onPressAndHold: { + QGroundControl.corePlugin.showTouchAreas = !QGroundControl.corePlugin.showTouchAreas + console.log("Press and hold", QGroundControl.corePlugin.showTouchAreas) + } + MessageDialog { - id: advancedModeConfirmation + id: advancedModeOnConfirmation title: qsTr("Advanced Mode") text: QGroundControl.corePlugin.showAdvancedUIMessage standardButtons: StandardButton.Yes | StandardButton.No onYes: { QGroundControl.corePlugin.showAdvancedUI = true - advancedModeConfirmation.close() + advancedModeOnConfirmation.close() + } + } + + MessageDialog { + id: advancedModeOffConfirmation + title: qsTr("Advanced Mode") + text: qsTr("Turn off Advanced Mode?") + standardButtons: StandardButton.Yes | StandardButton.No + onYes: { + QGroundControl.corePlugin.showAdvancedUI = false + advancedModeOffConfirmation.close() } } } From e56b1725f35afc0ffdf4bbef82833d307ee65f95 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 4 Aug 2023 15:15:25 -0700 Subject: [PATCH 017/118] Increase size of click area for flight mode change --- src/ui/toolbar/FlightModeMenuIndicator.qml | 44 +++++++++++++++------- src/ui/toolbar/MainStatusIndicator.qml | 19 +--------- 2 files changed, 31 insertions(+), 32 deletions(-) diff --git a/src/ui/toolbar/FlightModeMenuIndicator.qml b/src/ui/toolbar/FlightModeMenuIndicator.qml index dbc1fc13b0f..5ac65c808d1 100644 --- a/src/ui/toolbar/FlightModeMenuIndicator.qml +++ b/src/ui/toolbar/FlightModeMenuIndicator.qml @@ -16,9 +16,9 @@ import QGroundControl.MultiVehicleManager 1.0 import QGroundControl.ScreenTools 1.0 import QGroundControl.Palette 1.0 -RowLayout { - id: _root - spacing: 0 +Item { + id: _root + Layout.preferredWidth: rowLayout.width property real fontPointSize: ScreenTools.largeFontPointSize property var activeVehicle: QGroundControl.multiVehicleManager.activeVehicle @@ -68,19 +68,35 @@ RowLayout { } RowLayout { - Layout.fillWidth: true + id: rowLayout + spacing: 0 + height: parent.height + + QGCColoredImage { + id: flightModeIcon + width: ScreenTools.defaultFontPixelWidth * 2 + height: ScreenTools.defaultFontPixelHeight * 0.75 + fillMode: Image.PreserveAspectFit + mipmap: true + color: qgcPal.text + source: "/qmlimages/FlightModesComponentIcon.png" + Layout.alignment: Qt.AlignVCenter + } + + Item { + Layout.preferredWidth: ScreenTools.defaultFontPixelWidth / 2 + height: 1 + } QGCLabel { - text: activeVehicle ? activeVehicle.flightMode : qsTr("N/A", "No data to display") - font.pointSize: fontPointSize - Layout.alignment: Qt.AlignCenter - - MouseArea { - anchors.fill: parent - onClicked: { - mainWindow.showIndicatorPopup(_root, flightModeMenu) - } - } + text: activeVehicle ? activeVehicle.flightMode : qsTr("N/A", "No data to display") + font.pointSize: fontPointSize + Layout.alignment: Qt.AlignVCenter } } + + QGCMouseArea { + anchors.fill: parent + onClicked: mainWindow.showIndicatorPopup(_root, flightModeMenu) + } } diff --git a/src/ui/toolbar/MainStatusIndicator.qml b/src/ui/toolbar/MainStatusIndicator.qml index 8ff0fc9fe1b..1e2ff5f2c48 100644 --- a/src/ui/toolbar/MainStatusIndicator.qml +++ b/src/ui/toolbar/MainStatusIndicator.qml @@ -107,7 +107,7 @@ RowLayout { } } - MouseArea { + QGCMouseArea { anchors.left: parent.left anchors.right: parent.right anchors.verticalCenter: parent.verticalCenter @@ -122,23 +122,6 @@ RowLayout { height: 1 } - QGCColoredImage { - id: flightModeIcon - width: ScreenTools.defaultFontPixelWidth * 2 - height: ScreenTools.defaultFontPixelHeight * 0.75 - fillMode: Image.PreserveAspectFit - mipmap: true - color: qgcPal.text - source: "/qmlimages/FlightModesComponentIcon.png" - visible: flightModeMenu.visible - } - - Item { - Layout.preferredWidth: ScreenTools.defaultFontPixelWidth / 2 - height: 1 - visible: flightModeMenu.visible - } - FlightModeMenuIndicator { id: flightModeMenu Layout.preferredHeight: _root.height From e6929a3fd94e00b51960834e3033ef38cca2bede Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 8 Aug 2023 09:34:04 -0700 Subject: [PATCH 018/118] Switch date format to fix small screens --- src/AnalyzeView/LogDownloadPage.qml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/AnalyzeView/LogDownloadPage.qml b/src/AnalyzeView/LogDownloadPage.qml index 1ba34e72a8c..863274ac39a 100644 --- a/src/AnalyzeView/LogDownloadPage.qml +++ b/src/AnalyzeView/LogDownloadPage.qml @@ -84,7 +84,7 @@ AnalyzePage { if(d.getUTCFullYear() < 2010) return qsTr("Date Unknown") else - return d.toLocaleString() + return d.toLocaleString(undefined, "short") } } return "" From 1c90dba5401668b8bcde519105a9c1a29cccd33c Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 8 Aug 2023 12:15:02 -0700 Subject: [PATCH 019/118] Notify user of touch area toggle --- src/ui/MainRootWindow.qml | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/src/ui/MainRootWindow.qml b/src/ui/MainRootWindow.qml index 70845f1d9bc..ac7a16f1069 100644 --- a/src/ui/MainRootWindow.qml +++ b/src/ui/MainRootWindow.qml @@ -373,6 +373,7 @@ ApplicationWindow { onClicked: { if (mouse.modifiers & Qt.ControlModifier) { QGroundControl.corePlugin.showTouchAreas = !QGroundControl.corePlugin.showTouchAreas + showTouchAreasNotification.open() } else if (ScreenTools.isMobile || mouse.modifiers & Qt.ShiftModifier) { if(!QGroundControl.corePlugin.showAdvancedUI) { advancedModeOnConfirmation.open() @@ -385,7 +386,14 @@ ApplicationWindow { // This allows you to change this on mobile onPressAndHold: { QGroundControl.corePlugin.showTouchAreas = !QGroundControl.corePlugin.showTouchAreas - console.log("Press and hold", QGroundControl.corePlugin.showTouchAreas) + showTouchAreasNotification.open() + } + + MessageDialog { + id: showTouchAreasNotification + title: qsTr("Debug Touch Areas") + text: qsTr("Touch Area display toggled") + standardButtons: StandardButton.Ok } MessageDialog { From 09957713811c19e937084964b2e17eb814deac3e Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 8 Aug 2023 11:37:19 -0700 Subject: [PATCH 020/118] Update for latest Copter fence support --- .../APM/APMSafetyComponent.qml | 183 +++++++++--------- 1 file changed, 89 insertions(+), 94 deletions(-) diff --git a/src/AutoPilotPlugins/APM/APMSafetyComponent.qml b/src/AutoPilotPlugins/APM/APMSafetyComponent.qml index d46f26fbf99..8c75d700bb6 100644 --- a/src/AutoPilotPlugins/APM/APMSafetyComponent.qml +++ b/src/AutoPilotPlugins/APM/APMSafetyComponent.qml @@ -409,121 +409,116 @@ SetupPage { property Fact _fenceRadius: controller.getParameterFact(-1, "FENCE_RADIUS") property Fact _fenceType: controller.getParameterFact(-1, "FENCE_TYPE") + readonly property int _maxAltitudeFenceBitMask: 1 + readonly property int _circleFenceBitMask: 2 + readonly property int _polygonFenceBitMask: 4 + QGCLabel { - id: geoFenceLabel text: qsTr("GeoFence") font.family: ScreenTools.demiboldFontFamily } Rectangle { - id: geoFenceSettings - width: fenceAltMaxField.x + fenceAltMaxField.width + _margins - height: fenceAltMaxField.y + fenceAltMaxField.height + _margins + width: mainLayout.width + (_margins * 2) + height: mainLayout.height + (_margins * 2) color: ggcPal.windowShade - QGCCheckBox { - id: circleGeo - anchors.margins: _margins - anchors.left: parent.left - anchors.top: parent.top - text: qsTr("Circle GeoFence enabled") - checked: _fenceEnable.value != 0 && _fenceType.value & 2 - - onClicked: { - if (checked) { - if (_fenceEnable.value == 1) { - _fenceType.value |= 2 - } else { - _fenceEnable.value = 1 - _fenceType.value = 2 + ColumnLayout { + id: mainLayout + x: _margins + y: _margins + spacing: ScreenTools.defaultFontPixellHeight / 2 + + FactCheckBox { + id: enabledCheckBox + text: qsTr("Enabled") + fact: _fenceEnable + } + + GridLayout { + columns: 2 + enabled: enabledCheckBox.checked + + QGCCheckBox { + text: qsTr("Maximum Altitude") + checked: _fenceType.rawValue & _maxAltitudeFenceBitMask + + onClicked: { + if (checked) { + _fenceType.rawValue |= _maxAltitudeFenceBitMask + } else { + _fenceType.value &= ~_maxAltitudeFenceBitMask + } } - } else if (altitudeGeo.checked) { - _fenceType.value &= ~2 - } else { - _fenceEnable.value = 0 - _fenceType.value = 0 } - } - } - QGCCheckBox { - id: altitudeGeo - anchors.topMargin: _margins / 2 - anchors.left: circleGeo.left - anchors.top: circleGeo.bottom - text: qsTr("Altitude GeoFence enabled") - checked: _fenceEnable.value != 0 && _fenceType.value & 1 - - onClicked: { - if (checked) { - if (_fenceEnable.value == 1) { - _fenceType.value |= 1 - } else { - _fenceEnable.value = 1 - _fenceType.value = 1 + FactTextField { + fact: _fenceAltMax + } + + QGCCheckBox { + text: qsTr("Circle centered on Home") + checked: _fenceType.rawValue & _circleFenceBitMask + + onClicked: { + if (checked) { + _fenceType.rawValue |= _circleFenceBitMask + } else { + _fenceType.value &= ~_circleFenceBitMask + } } - } else if (circleGeo.checked) { - _fenceType.value &= ~1 - } else { - _fenceEnable.value = 0 - _fenceType.value = 0 } - } - } - QGCRadioButton { - id: geoReportRadio - anchors.margins: _margins - anchors.left: parent.left - anchors.top: altitudeGeo.bottom - text: qsTr("Report only") - checked: _fenceAction.value == 0 + FactTextField { + fact: _fenceRadius + showUnits: true + } - onClicked: _fenceAction.value = 0 - } + QGCCheckBox { + text: qsTr("Inclusion/Exclusion Circles+Polygons") + checked: _fenceType.rawValue & _polygonFenceBitMask + + onClicked: { + if (checked) { + _fenceType.rawValue |= _polygonFenceBitMask + } else { + _fenceType.value &= ~_polygonFenceBitMask + } + } + } - QGCRadioButton { - id: geoRTLRadio - anchors.topMargin: _margins / 2 - anchors.left: circleGeo.left - anchors.top: geoReportRadio.bottom - text: qsTr("RTL or Land") - checked: _fenceAction.value == 1 + Item { + height: 1 + width: 1 + } + } // GridLayout - onClicked: _fenceAction.value = 1 - } + Item { + height: 1 + width: 1 + } - QGCLabel { - id: fenceRadiusLabel - anchors.left: circleGeo.left - anchors.baseline: fenceRadiusField.baseline - text: qsTr("Max radius:") - } + GridLayout { + columns: 2 + enabled: enabledCheckBox.checked - FactTextField { - id: fenceRadiusField - anchors.topMargin: _margins - anchors.left: fenceAltMaxField.left - anchors.top: geoRTLRadio.bottom - fact: _fenceRadius - showUnits: true - } + QGCLabel { + text: qsTr("Breach action") + } - QGCLabel { - id: fenceAltMaxLabel - anchors.left: circleGeo.left - anchors.baseline: fenceAltMaxField.baseline - text: qsTr("Max altitude:") - } + FactComboBox { + sizeToContents: true + fact: _fenceAction + } - FactTextField { - id: fenceAltMaxField - anchors.topMargin: _margins / 2 - anchors.leftMargin: _margins - anchors.left: fenceAltMaxLabel.right - anchors.top: fenceRadiusField.bottom - fact: _fenceAltMax - showUnits: true + QGCLabel { + text: qsTr("Fence margin") + } + + FactTextField { + fact: _fenceMargin + } + } } } // Rectangle - GeoFence Settings } // Column - GeoFence Settings From 72c0f4e60bd354041d2d80476156818bb858fa75 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 8 Aug 2023 11:37:40 -0700 Subject: [PATCH 021/118] Add support for mavlink FENCE_STATUS --- src/Vehicle/Vehicle.cc | 39 +++++++++++++++++++++++++++++++++++++++ src/Vehicle/Vehicle.h | 1 + 2 files changed, 40 insertions(+) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 8ae6b6b9d27..e4d12f99765 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -742,6 +742,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes case MAVLINK_MSG_ID_OBSTACLE_DISTANCE: _handleObstacleDistance(message); break; + case MAVLINK_MSG_ID_FENCE_STATUS: + _handleFenceStatus(message); + break; case MAVLINK_MSG_ID_EVENT: case MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE: @@ -4173,6 +4176,42 @@ void Vehicle::_handleObstacleDistance(const mavlink_message_t& message) _objectAvoidance->update(&o); } +void Vehicle::_handleFenceStatus(const mavlink_message_t& message) +{ + mavlink_fence_status_t fenceStatus; + + mavlink_msg_fence_status_decode(&message, &fenceStatus); + + qCDebug(VehicleLog) << "_handleFenceStatus breach_status" << fenceStatus.breach_status; + + static qint64 lastUpdate = 0; + qint64 now = QDateTime::currentMSecsSinceEpoch(); + if (fenceStatus.breach_status == 1) { + if (now - lastUpdate > 3000) { + lastUpdate = now; + QString breachTypeStr; + switch (fenceStatus.breach_type) { + case FENCE_BREACH_NONE: + return; + case FENCE_BREACH_MINALT: + breachTypeStr = tr("minimum altitude"); + break; + case FENCE_BREACH_MAXALT: + breachTypeStr = tr("maximum altitude"); + break; + case FENCE_BREACH_BOUNDARY: + breachTypeStr = tr("boundary"); + break; + default: + break; + } + + qgcApp()->toolbox()->audioOutput()->say(breachTypeStr + " " + tr("fence breached")); + } + } else { + lastUpdate = now; + } +} void Vehicle::updateFlightDistance(double distance) { _flightDistanceFact.setRawValue(_flightDistanceFact.rawValue().toDouble() + distance); diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index a2ebc5a26c9..fedab4f2bb0 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -1059,6 +1059,7 @@ private slots: void _handleOrbitExecutionStatus (const mavlink_message_t& message); void _handleGimbalOrientation (const mavlink_message_t& message); void _handleObstacleDistance (const mavlink_message_t& message); + void _handleFenceStatus (const mavlink_message_t& message); void _handleEvent(uint8_t comp_id, std::unique_ptr event); // ArduPilot dialect messages #if !defined(NO_ARDUPILOT_DIALECT) From a2536a7fba8c725f57a187f1e349de3d79f7837e Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Wed, 9 Aug 2023 15:47:28 -0700 Subject: [PATCH 022/118] New translations qgc.ts (Chinese Simplified) --- translations/qgc_source_zh_CN.ts | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/translations/qgc_source_zh_CN.ts b/translations/qgc_source_zh_CN.ts index d2ad7d4a256..b8afbb29533 100644 --- a/translations/qgc_source_zh_CN.ts +++ b/translations/qgc_source_zh_CN.ts @@ -8263,7 +8263,7 @@ Click Ok to start the auto-tuning process. Toggle Arm - 拨杆解锁 + 切换锁定 From c7b40691c1acf63bd664cbb84962daac6b2dfe62 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Wed, 9 Aug 2023 15:47:29 -0700 Subject: [PATCH 023/118] New translations qgc-json.ts (Chinese Simplified) --- translations/qgc_json_zh_CN.ts | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/translations/qgc_json_zh_CN.ts b/translations/qgc_json_zh_CN.ts index 26ae498d594..fae275b6a56 100644 --- a/translations/qgc_json_zh_CN.ts +++ b/translations/qgc_json_zh_CN.ts @@ -595,7 +595,7 @@ .mavCmdInfo[MAV_CMD_NAV_PATHPLANNING].param2.label, Full planning - 本地规划 + 全面规划 .mavCmdInfo[MAV_CMD_NAV_PATHPLANNING].param2.enumStrings, @@ -625,7 +625,7 @@ .mavCmdInfo[MAV_CMD_NAV_ALTITUDE_WAIT].friendlyName, Altitude wait - 高度差 + 高度等待 .mavCmdInfo[MAV_CMD_NAV_VTOL_TAKEOFF].friendlyName, @@ -1435,7 +1435,7 @@ .mavCmdInfo[MAV_CMD_DO_GRIPPER].param1.label, Gripper id - 夹持器 + 夹持器 id .mavCmdInfo[MAV_CMD_DO_GRIPPER].param2.label, From 4474702f4db466e7cef85ce82f803a5b8d075253 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Thu, 10 Aug 2023 13:05:11 -0700 Subject: [PATCH 024/118] Android supports no serial/bluetooth build and home app Fixes --- QGCCommon.pri | 7 ++-- android.pri | 64 ++++++++++++++++++++++++++----------- android/AndroidManifest.xml | 6 +--- qgroundcontrol.pro | 12 +++---- 4 files changed, 55 insertions(+), 34 deletions(-) diff --git a/QGCCommon.pri b/QGCCommon.pri index 31ae0f4cda5..d3e1c7888df 100644 --- a/QGCCommon.pri +++ b/QGCCommon.pri @@ -113,13 +113,14 @@ linux { } } else : ios { message("iOS build") - CONFIG += iOSBuild MobileBuild app_bundle NoSerialBuild + CONFIG += iOSBuild MobileBuild app_bundle CONFIG -= bitcode DEFINES += __ios__ DEFINES += QGC_NO_GOOGLE_MAPS DEFINES += NO_SERIAL_LINK DEFINES += QGC_DISABLE_UVC DEFINES += QGC_GST_TAISYNC_ENABLED + DEFINES += NO_SERIAL_LINK QMAKE_IOS_DEPLOYMENT_TARGET = 11.0 QMAKE_APPLE_TARGETED_DEVICE_FAMILY = 1,2 # Universal QMAKE_LFLAGS += -Wl,-no_pie @@ -141,7 +142,7 @@ linux|macx|ios { } } -NoSerialBuild { +contains(DEFINES, NO_SERIAL_LINK) { message("Serial port support disabled") } @@ -197,6 +198,8 @@ exists ($$PWD/.git) { DEFINES += APP_VERSION_STR=\"\\\"$$APP_VERSION_STR\\\"\" AndroidBuild { + QGC_ANDROID_PACKAGE = org.mavlink.qgroundcontrol + message(VERSION $${VERSION}) MAJOR_VERSION = $$section(VERSION, ".", 0, 0) MINOR_VERSION = $$section(VERSION, ".", 1, 1) diff --git a/android.pri b/android.pri index 3539bd44035..641121f553e 100644 --- a/android.pri +++ b/android.pri @@ -1,41 +1,68 @@ -include($$PWD/libs/qtandroidserialport/src/qtandroidserialport.pri) -message("Adding Serial Java Classes") QT += androidextras -ANDROID_PACKAGE_SOURCE_DIR = $$PWD/android +include($$PWD/libs/qtandroidserialport/src/qtandroidserialport.pri) + +ANDROID_PACKAGE_SOURCE_DIR = $$OUT_PWD/ANDROID_PACKAGE_SOURCE_DIR # Tells Qt location of package files for build +ANDROID_PACKAGE_QGC_SOURCE_DIR = $$PWD/android # Original location of QGC package files +ANDROID_PACKAGE_CUSTOM_SOURCE_DIR = $$PWD/custom/android # Original location for custom build override package files + +# We always move the package files to the ANDROID_PACKAGE_SOURCE_DIR build dir so we can modify the manifest as needed -android_source_dir_target.commands = echo Updating Android Manifest +android_source_dir_target.target = $$ANDROID_PACKAGE_QGC_SOURCE_DIR/AndroidManifest.xml +android_source_dir_target.commands = \ + $$QMAKE_MKDIR $$ANDROID_PACKAGE_SOURCE_DIR && \ + $$QMAKE_COPY_DIR $$ANDROID_PACKAGE_QGC_SOURCE_DIR/* $$ANDROID_PACKAGE_SOURCE_DIR +PRE_TARGETDEPS += $$android_source_dir_target.target +QMAKE_EXTRA_TARGETS += android_source_dir_target android_source_dir_target.depends = FORCE -exists($$PWD/custom/android) { - message("Merging $$PWD/custom/android/ -> $$PWD/android/") +# Custom builds can override android package file - ANDROID_PACKAGE_SOURCE_DIR = $$OUT_PWD/ANDROID_PACKAGE_SOURCE_DIR - android_source_dir_target.target = android_source_dir - PRE_TARGETDEPS += $$android_source_dir_target.target - QMAKE_EXTRA_TARGETS += android_source_dir_target +exists($$ANDROID_PACKAGE_CUSTOM_SOURCE_DIR) { + message("Merging$$ $$ANDROID_PACKAGE_QGC_SOURCE_DIR and $$ANDROID_PACKAGE_CUSTOM_SOURCE_DIR to $$ANDROID_PACKAGE_SOURCE_DIR") + android_source_dir_target.target = $$ANDROID_PACKAGE_CUSTOM_SOURCE_DIR/AndroidManifest.xml android_source_dir_target.commands = $$android_source_dir_target.commands && \ - $$QMAKE_MKDIR $$ANDROID_PACKAGE_SOURCE_DIR && \ - $$QMAKE_COPY_DIR $$PWD/android/* $$OUT_PWD/ANDROID_PACKAGE_SOURCE_DIR && \ - $$QMAKE_COPY_DIR $$PWD/custom/android/* $$OUT_PWD/ANDROID_PACKAGE_SOURCE_DIR && \ + $$QMAKE_COPY_DIR $$ANDROID_PACKAGE_CUSTOM_SOURCE_DIR/* $$ANDROID_PACKAGE_SOURCE_DIR && \ $$QMAKE_STREAM_EDITOR -i \"s/package=\\\"org.mavlink.qgroundcontrol\\\"/package=\\\"$$QGC_ANDROID_PACKAGE\\\"/\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml } -NoSerialBuild { +# Insert package name into manifest file + +android_source_dir_target.commands = $$android_source_dir_target.commands && \ + $$QMAKE_STREAM_EDITOR -i \"s/%%QGC_INSERT_PACKAGE_NAME%%/$$QGC_ANDROID_PACKAGE/\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml + +# Update manifest activity intent filter as needed + +QGC_INSERT_ACTIVITY_INTENT_FILTER = "" +AndroidHomeApp { + # QGC is the android home application + QGC_INSERT_ACTIVITY_INTENT_FILTER = $$QGC_INSERT_ACTIVITY_INTENT_FILTER "\r\n\r\n" +} +!contains(DEFINES, NO_SERIAL_LINK) { + # Add usb device support + QGC_INSERT_ACTIVITY_INTENT_FILTER = $$QGC_INSERT_ACTIVITY_INTENT_FILTER "\r\n\r\n\r\n" +} +contains(DEFINES, QGC_ENABLE_BLUETOOTH) { + QGC_INSERT_ACTIVITY_INTENT_FILTER = $$QGC_INSERT_ACTIVITY_INTENT_FILTER "\r\n\r\n" +} +android_source_dir_target.commands = $$android_source_dir_target.commands && \ + $$QMAKE_STREAM_EDITOR -i \"s//$$QGC_INSERT_ACTIVITY_INTENT_FILTER/\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml + +# Update manifest activity meta data as needed + +contains(DEFINES, NO_SERIAL_LINK) { # No need to add anything to manifest - android_source_dir_target.commands = $$android_source_dir_target.commands && \ - $$QMAKE_STREAM_EDITOR -i \"s///\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml android_source_dir_target.commands = $$android_source_dir_target.commands && \ $$QMAKE_STREAM_EDITOR -i \"s///\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml } else { # Updates the manifest for usb device support - android_source_dir_target.commands = $$android_source_dir_target.commands && \ - $$QMAKE_STREAM_EDITOR -i \"s//\r\n\r\n/\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml android_source_dir_target.commands = $$android_source_dir_target.commands && \ $$QMAKE_STREAM_EDITOR -i \"s//\r\n\r\n/\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml } +# OTHER_FILES makes the specified files be visible in Qt Creator for editing + exists($$PWD/custom/android/AndroidManifest.xml) { OTHER_FILES += \ $$PWD/custom/android/AndroidManifest.xml @@ -62,7 +89,6 @@ OTHER_FILES += \ $$PWD/android/src/org/freedesktop/gstreamer/androidmedia/GstAhsCallback.java \ $$PWD/android/src/org/freedesktop/gstreamer/androidmedia/GstAmcOnFrameAvailableListener.java - DISTFILES += \ $$PWD/android/gradle/wrapper/gradle-wrapper.jar \ $$PWD/android/gradlew \ diff --git a/android/AndroidManifest.xml b/android/AndroidManifest.xml index 63ec9970381..15c35bc6b8e 100644 --- a/android/AndroidManifest.xml +++ b/android/AndroidManifest.xml @@ -1,5 +1,5 @@ - + @@ -13,11 +13,7 @@ - - - - diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index f3d7704a173..73ea5522420 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -796,11 +796,7 @@ contains (DEFINES, QGC_ENABLE_PAIRING) { } } -contains(DEFINES, NO_SERIAL_LINK) { - CONFIG += NoSerialBuild -} - -!NoSerialBuild { +!contains(DEFINES, NO_SERIAL_LINK) { HEADERS += \ src/comm/QGCSerialPortInfo.h \ src/comm/SerialLink.h \ @@ -1031,7 +1027,7 @@ SOURCES += \ src/comm/MockLinkMissionItemHandler.cc \ } -!NoSerialBuild { +!contains(DEFINES, NO_SERIAL_LINK) { SOURCES += \ src/comm/QGCSerialPortInfo.cc \ src/comm/SerialLink.cc \ @@ -1086,7 +1082,7 @@ HEADERS+= \ src/FirmwarePlugin/FirmwarePluginManager.h \ src/VehicleSetup/VehicleComponent.h \ -!MobileBuild { !NoSerialBuild { +!MobileBuild { !contains(DEFINES, NO_SERIAL_LINK) { HEADERS += \ src/VehicleSetup/Bootloader.h \ src/VehicleSetup/FirmwareImage.h \ @@ -1108,7 +1104,7 @@ SOURCES += \ src/FirmwarePlugin/FirmwarePluginManager.cc \ src/VehicleSetup/VehicleComponent.cc \ -!MobileBuild { !NoSerialBuild { +!MobileBuild { !contains(DEFINES, NO_SERIAL_LINK) { SOURCES += \ src/VehicleSetup/Bootloader.cc \ src/VehicleSetup/FirmwareImage.cc \ From 4cca4c88841de8cffc82baea41d07a406d7b558e Mon Sep 17 00:00:00 2001 From: James Mare Date: Tue, 1 Aug 2023 21:07:48 -0700 Subject: [PATCH 025/118] Fix skipping of NMEA serial ports QGCSerialPortInfo skips over serial ports which are not the first in any composite device. However this is how some internal NMEA GPS's present. So if the description contains 'NMEA', dont skip them. --- src/comm/QGCSerialPortInfo.cc | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/comm/QGCSerialPortInfo.cc b/src/comm/QGCSerialPortInfo.cc index 94acb81f2bc..ab169a30898 100644 --- a/src/comm/QGCSerialPortInfo.cc +++ b/src/comm/QGCSerialPortInfo.cc @@ -305,8 +305,12 @@ QList QGCSerialPortInfo::availablePorts(void) VidPidPair_t vidPid(portInfo.vendorIdentifier(), portInfo.productIdentifier()); if (seenSerialNumbers.contains(vidPid) && seenSerialNumbers[vidPid].contains(portInfo.serialNumber())) { // Some boards are a composite USB device, with the first port being mavlink and the second something else. We only expose to first mavlink port. - qCDebug(QGCSerialPortInfoLog) << "Skipping secondary port on same device" << portInfo.portName() << portInfo.vendorIdentifier() << portInfo.productIdentifier() << portInfo.serialNumber(); - continue; + // However internal NMEA devices can present like this, so dont skip anything with NMEA in description + if(!portInfo.description().contains("NMEA")) + { + qCDebug(QGCSerialPortInfoLog) << "Skipping secondary port on same device" << portInfo.portName() << portInfo.vendorIdentifier() << portInfo.productIdentifier() << portInfo.serialNumber(); + continue; + } } seenSerialNumbers[vidPid].append(portInfo.serialNumber()); } From aa950c9aed736628de4df620b1db7ee580db3449 Mon Sep 17 00:00:00 2001 From: James Mare Date: Tue, 1 Aug 2023 21:09:27 -0700 Subject: [PATCH 026/118] Fix UI Displaying incorrect serial port list The list of serial ports that ended up in the UI was from QSerialPortInfo::availablePorts(), however the list available to be used is a filtered list from QGCSerialPortInfo::availablePorts() Changed so that the UI pulls the filtered list, and no ports present which dont actually work. --- src/comm/LinkManager.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index 1215516f0fe..864ef8cd430 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -713,8 +713,8 @@ void LinkManager::_updateSerialPorts() _commPortList.clear(); _commPortDisplayList.clear(); #ifndef NO_SERIAL_LINK - QList portList = QSerialPortInfo::availablePorts(); - for (const QSerialPortInfo &info: portList) + QList portList = QGCSerialPortInfo::availablePorts(); + for (const QGCSerialPortInfo &info: portList) { QString port = info.systemLocation().trimmed(); _commPortList += port; From 6a62796e0b8149f5d0bf2602cac373f602253c3b Mon Sep 17 00:00:00 2001 From: James Mare Date: Tue, 1 Aug 2023 22:01:08 -0700 Subject: [PATCH 027/118] PositionManager: clear values on changing source This prevents getting stuck with old values latched in the UI. Which would happen if the new position source didn't get an update. --- src/PositionManager/PositionManager.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/src/PositionManager/PositionManager.cpp b/src/PositionManager/PositionManager.cpp index 0855f141257..78fbd8f676f 100644 --- a/src/PositionManager/PositionManager.cpp +++ b/src/PositionManager/PositionManager.cpp @@ -153,6 +153,17 @@ void QGCPositionManager::setPositionSource(QGCPositionManager::QGCPositionSource if (_currentSource != nullptr) { _currentSource->stopUpdates(); disconnect(_currentSource); + + // Reset all values so we dont get stuck on old values + _geoPositionInfo = QGeoPositionInfo(); + _gcsPosition = QGeoCoordinate(); + _gcsHeading = qQNaN(); + _gcsPositionHorizontalAccuracy = std::numeric_limits::infinity(); + + emit gcsPositionChanged(_gcsPosition); + emit gcsHeadingChanged(_gcsHeading); + emit positionInfoUpdated(_geoPositionInfo); + emit gcsPositionHorizontalAccuracyChanged(); } if (qgcApp()->runningUnitTests()) { From 1d59706e2b1d35465307bad03151a0bb15ae7b9c Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 11 Aug 2023 16:02:13 -0700 Subject: [PATCH 028/118] Fix normal and adsb vehicle sizing Fix --- src/FlightDisplay/FlyViewMap.qml | 1 + src/FlightMap/MapItems/VehicleMapItem.qml | 10 +++++----- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/src/FlightDisplay/FlyViewMap.qml b/src/FlightDisplay/FlyViewMap.qml index 2861e02a8e9..4c2b5208a65 100644 --- a/src/FlightDisplay/FlyViewMap.qml +++ b/src/FlightDisplay/FlyViewMap.qml @@ -265,6 +265,7 @@ FlightMap { heading: object.heading alert: object.alert map: _root + size: pipMode ? ScreenTools.defaultFontPixelHeight : ScreenTools.defaultFontPixelHeight * 2.5 z: QGroundControl.zOrderVehicles } } diff --git a/src/FlightMap/MapItems/VehicleMapItem.qml b/src/FlightMap/MapItems/VehicleMapItem.qml index 176f479a3c3..49c81060146 100644 --- a/src/FlightMap/MapItems/VehicleMapItem.qml +++ b/src/FlightMap/MapItems/VehicleMapItem.qml @@ -19,12 +19,14 @@ import QGroundControl.Controls 1.0 /// Marker for displaying a vehicle location on the map MapQuickItem { + id: _root + property var vehicle /// Vehicle object, undefined for ADSB vehicle property var map property double altitude: Number.NaN ///< NAN to not show property string callsign: "" ///< Vehicle callsign property double heading: vehicle ? vehicle.heading.value : Number.NaN ///< Vehicle heading, NAN for none - property real size: _adsbVehicle ? _adsbSize : _uavSize /// Size for icon + property real size: ScreenTools.defaultFontPixelHeight * 3 /// Default size for icon, most usage overrides this property bool alert: false /// Collision alert anchorPoint.x: vehicleItem.width / 2 @@ -33,8 +35,6 @@ MapQuickItem { property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property bool _adsbVehicle: vehicle ? false : true - property real _uavSize: ScreenTools.defaultFontPixelHeight * 5 - property real _adsbSize: ScreenTools.defaultFontPixelHeight * 2.5 property var _map: map property bool _multiVehicle: QGroundControl.multiVehicleManager.vehicles.count > 1 @@ -65,8 +65,8 @@ MapQuickItem { id: vehicleIcon source: _adsbVehicle ? (alert ? "/qmlimages/AlertAircraft.svg" : "/qmlimages/AwarenessAircraft.svg") : vehicle.vehicleImageOpaque mipmap: true - width: size - sourceSize.width: size + width: _root.size + sourceSize.width: _root.size fillMode: Image.PreserveAspectFit transform: Rotation { origin.x: vehicleIcon.width / 2 From f0b5646b4ccc85dcdbca104230c1bf06626fd50e Mon Sep 17 00:00:00 2001 From: James Mare Date: Fri, 4 Aug 2023 12:08:22 +1000 Subject: [PATCH 029/118] Rework Vehicle Joystick Handling This fixes a number of issues with the way joysticks were handled in a multi vehicle context. I reworked the way vehicle determine to enable and capture the joystick input, as well as seperating setJoystickEnable from saveJoystick to seperate runtime and saved state. --- src/Joystick/Joystick.cc | 13 ++- src/Joystick/Joystick.h | 4 +- src/QGCLoggingCategory.cc | 2 + src/QGCLoggingCategory.h | 1 + src/Vehicle/Vehicle.cc | 95 +++++++++++++------- src/Vehicle/Vehicle.h | 9 +- src/VehicleSetup/JoystickConfigController.cc | 1 + src/VehicleSetup/JoystickConfigGeneral.qml | 5 +- 8 files changed, 89 insertions(+), 41 deletions(-) diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index 670cc777e3f..3217d6b7461 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -21,7 +21,7 @@ #include -QGC_LOGGING_CATEGORY(JoystickLog, "JoystickLog") +// JoystickLog Category declaration moved to QGCLoggingCategory.cc to allow access in Vehicle QGC_LOGGING_CATEGORY(JoystickValuesLog, "JoystickValuesLog") const char* Joystick::_settingsGroup = "Joysticks"; @@ -128,6 +128,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC _updateTXModeSettingsKey(_multiVehicleManager->activeVehicle()); _loadSettings(); connect(_multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &Joystick::_activeVehicleChanged); + connect(qgcApp()->toolbox()->multiVehicleManager()->vehicles(), &QmlObjectListModel::countChanged, this, &Joystick::_vehicleCountChanged); _customMavCommands = JoystickMavCommand::load("JoystickMavCommands.json"); } @@ -226,6 +227,16 @@ void Joystick::_activeVehicleChanged(Vehicle* activeVehicle) } } +void Joystick::_vehicleCountChanged(int count) +{ + if(count == 0) + { + // then the last vehicle has been deleted + qCDebug(JoystickLog) << "Stopping joystick thread due to last active vehicle deletion"; + this->stopPolling(); + } +} + void Joystick::_loadSettings() { QSettings settings; diff --git a/src/Joystick/Joystick.h b/src/Joystick/Joystick.h index 7da35114712..d791f1ed25e 100644 --- a/src/Joystick/Joystick.h +++ b/src/Joystick/Joystick.h @@ -21,7 +21,7 @@ #include "MultiVehicleManager.h" #include "JoystickMavCommand.h" -Q_DECLARE_LOGGING_CATEGORY(JoystickLog) +// JoystickLog Category declaration moved to QGCLoggingCategory.cc to allow access in Vehicle Q_DECLARE_LOGGING_CATEGORY(JoystickValuesLog) Q_DECLARE_METATYPE(GRIPPER_ACTIONS) @@ -370,4 +370,6 @@ class Joystick : public QThread private slots: void _activeVehicleChanged(Vehicle* activeVehicle); + void _vehicleCountChanged(int count); + }; diff --git a/src/QGCLoggingCategory.cc b/src/QGCLoggingCategory.cc index 54d2cadfa39..791de78414e 100644 --- a/src/QGCLoggingCategory.cc +++ b/src/QGCLoggingCategory.cc @@ -29,6 +29,8 @@ QGC_LOGGING_CATEGORY(GuidedActionsControllerLog, "GuidedActionsControllerLog" QGC_LOGGING_CATEGORY(ADSBVehicleManagerLog, "ADSBVehicleManagerLog") QGC_LOGGING_CATEGORY(LocalizationLog, "LocalizationLog") QGC_LOGGING_CATEGORY(VideoAllLog, kVideoAllLogCategory) +QGC_LOGGING_CATEGORY(JoystickLog, "JoystickLog") + QGCLoggingCategoryRegister* _instance = nullptr; const char* QGCLoggingCategoryRegister::_filterRulesSettingsGroup = "LoggingFilters"; diff --git a/src/QGCLoggingCategory.h b/src/QGCLoggingCategory.h index 7b549118426..e4d1de3bc1d 100644 --- a/src/QGCLoggingCategory.h +++ b/src/QGCLoggingCategory.h @@ -24,6 +24,7 @@ Q_DECLARE_LOGGING_CATEGORY(GuidedActionsControllerLog) Q_DECLARE_LOGGING_CATEGORY(ADSBVehicleManagerLog) Q_DECLARE_LOGGING_CATEGORY(LocalizationLog) Q_DECLARE_LOGGING_CATEGORY(VideoAllLog) // turns on all individual QGC video logs +Q_DECLARE_LOGGING_CATEGORY(JoystickLog) /// @def QGC_LOGGING_CATEGORY /// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index e4d12f99765..4fd1e1d520b 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -179,8 +179,7 @@ Vehicle::Vehicle(LinkInterface* link, { _linkManager = _toolbox->linkManager(); - connect(_joystickManager, &JoystickManager::activeJoystickChanged, this, &Vehicle::_loadSettings); - connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleAvailableChanged, this, &Vehicle::_activeVehicleAvailableChanged); + connect(_joystickManager, &JoystickManager::activeJoystickChanged, this, &Vehicle::_loadJoystickSettings); connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &Vehicle::_activeVehicleChanged); _mavlink = _toolbox->mavlinkProtocol(); @@ -475,6 +474,9 @@ void Vehicle::_commonInit() _settingsManager->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDPH264); _settingsManager->videoSettings()->lowLatencyMode()->setRawValue(true); } + + // enable Joystick if appropriate + _loadJoystickSettings(); } Vehicle::~Vehicle() @@ -489,10 +491,6 @@ Vehicle::~Vehicle() delete _mav; _mav = nullptr; - - if (_joystickManager) { - _startJoystick(false); - } } void Vehicle::prepareDelete() @@ -2082,34 +2080,37 @@ void Vehicle::resetErrorLevelMessages() } } -void Vehicle::_loadSettings() +// this function called in three cases: +// 1. On constructor of vehicle, to see if we should enable a joystick +// 2. When there is a new active joystick +// 3. When the active joystick is disconnected (even if there isnt a new one) +void Vehicle::_loadJoystickSettings() { QSettings settings; settings.beginGroup(QString(_settingsGroup).arg(_id)); - // Joystick enabled is a global setting so first make sure there are any joysticks connected - if (_toolbox->joystickManager()->joysticks().count()) { + const bool _useButtonsOnly = qgcApp()->toolbox()->corePlugin()->options()->joystickUseButtonsOnly(); + + if (!_useButtonsOnly && _toolbox->joystickManager()->activeJoystick()) { + qCDebug(JoystickLog) << "Vehicle " << this->id() << " Notified of an active joystick. Loading setting joystickenabled: " << settings.value(_joystickEnabledSettingsKey, false).toBool(); setJoystickEnabled(settings.value(_joystickEnabledSettingsKey, false).toBool()); - _startJoystick(true); } -} - -void Vehicle::_activeVehicleAvailableChanged(bool isActiveVehicleAvailable) -{ - // if there is no longer an active vehicle, disconnect the joystick - if(!isActiveVehicleAvailable) { + else if(_useButtonsOnly) + { + // in a build with _useButtonsOnly set, joystickenable should always be left false + // this prevents the sticks from doing anything + qCDebug(JoystickLog) << "Vehicle " << this->id() << " Skipping Load of Joystick Settings because QCC Options useButtonsOnly is set"; setJoystickEnabled(false); } -} - -void Vehicle::_activeVehicleChanged(Vehicle *newActiveVehicle) -{ - if(newActiveVehicle == this) { - // this vehicle is the newly active vehicle - setJoystickEnabled(true); + else + { + qCDebug(JoystickLog) << "Vehicle " << this->id() << " Notified that there is no active joystick"; + setJoystickEnabled(false); } } -void Vehicle::_saveSettings() +// This is called from the UI when a deliberate action is taken to enable or disable the joystick +// This save allows the joystick enable state to persist restarts, disconnections of the joystick etc +void Vehicle::saveJoystickSettings() { QSettings settings; settings.beginGroup(QString(_settingsGroup).arg(_id)); @@ -2117,6 +2118,7 @@ void Vehicle::_saveSettings() // The joystick enabled setting should only be changed if a joystick is present // since the checkbox can only be clicked if one is present if (_toolbox->joystickManager()->joysticks().count()) { + qCDebug(JoystickLog) << "Vehicle " << this->id() << " Saving setting joystickenabled: " << _joystickEnabled; settings.setValue(_joystickEnabledSettingsKey, _joystickEnabled); } } @@ -2128,25 +2130,50 @@ bool Vehicle::joystickEnabled() const void Vehicle::setJoystickEnabled(bool enabled) { + if (enabled){ + qCDebug(JoystickLog) << "Vehicle " << this->id() << " Joystick Enabled"; + } + else { + qCDebug(JoystickLog) << "Vehicle " << this->id() << " Joystick Disabled"; + } + + // _joystickEnabled is the runtime state - it determines whether a vehicle is using joystick data when it is active _joystickEnabled = enabled; - _startJoystick(_joystickEnabled); - _saveSettings(); + + // if we are the active vehicle, call start polling on the active joystick + // This routes the joystick signals to this vehicle + // We do this even if we are disabling the joystick + // because it will trigger disconnection of the signals + if (_toolbox->multiVehicleManager()->activeVehicle() == this){ + _captureJoystick(); + } + emit joystickEnabledChanged(_joystickEnabled); } -void Vehicle::_startJoystick(bool start) +void Vehicle::_activeVehicleChanged(Vehicle *newActiveVehicle) +{ + // the new active vehicle should always capture the joystick + // even if the new active vehicle has joystick disabled + // capturing the joystick will stop the joystick data going to the inactive vehicle + if (newActiveVehicle == this){ + qCDebug(JoystickLog) << "Vehicle " << this->id() << " is the new active vehicle"; + _captureJoystick(); + } +} + +// tells the active joystick where to send data +void Vehicle::_captureJoystick() { Joystick* joystick = _joystickManager->activeJoystick(); - if (joystick) { - if (start) { - joystick->startPolling(this); - } else { - joystick->stopPolling(); - joystick->wait(500); - } + + if(joystick){ + qCDebug(JoystickLog) << "Vehicle " << this->id() << " Capture Joystick"; + joystick->startPolling(this); } } + QGeoCoordinate Vehicle::homePosition() { return _homePosition; diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index fedab4f2bb0..b8f9b7ca978 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -463,6 +463,9 @@ class Vehicle : public FactGroup /// Set home from flight map coordinate Q_INVOKABLE void doSetHome(const QGeoCoordinate& coord); + /// Save the joystick enable setting to the settings group + Q_INVOKABLE void saveJoystickSettings(void); + bool isInitialConnectComplete() const; bool guidedModeSupported () const; bool pauseVehicleSupported () const; @@ -1031,11 +1034,9 @@ private slots: void _gotProgressUpdate (float progressValue); private: - void _loadSettings (); - void _activeVehicleAvailableChanged (bool isActiveVehicleAvailable); + void _loadJoystickSettings (); void _activeVehicleChanged (Vehicle* newActiveVehicle); - void _saveSettings (); - void _startJoystick (bool start); + void _captureJoystick (); void _handlePing (LinkInterface* link, mavlink_message_t& message); void _handleHomePosition (mavlink_message_t& message); void _handleHeartbeat (mavlink_message_t& message); diff --git a/src/VehicleSetup/JoystickConfigController.cc b/src/VehicleSetup/JoystickConfigController.cc index 64f62004e99..256f450aff0 100644 --- a/src/VehicleSetup/JoystickConfigController.cc +++ b/src/VehicleSetup/JoystickConfigController.cc @@ -538,6 +538,7 @@ void JoystickConfigController::_writeCalibration() Vehicle* vehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); if (vehicle) { vehicle->setJoystickEnabled(true); + vehicle->saveJoystickSettings(); } } diff --git a/src/VehicleSetup/JoystickConfigGeneral.qml b/src/VehicleSetup/JoystickConfigGeneral.qml index e6b8428fb36..4e846d05eed 100644 --- a/src/VehicleSetup/JoystickConfigGeneral.qml +++ b/src/VehicleSetup/JoystickConfigGeneral.qml @@ -42,7 +42,10 @@ Item { QGCCheckBox { id: enabledSwitch enabled: _activeJoystick ? _activeJoystick.calibrated : false - onClicked: globals.activeVehicle.joystickEnabled = checked + onClicked: { + globals.activeVehicle.joystickEnabled = checked + globals.activeVehicle.saveJoystickSettings() + } Component.onCompleted: { checked = globals.activeVehicle.joystickEnabled } From 0c428b5cfcc0679e616b55e0265d9c6eac8cf39b Mon Sep 17 00:00:00 2001 From: James Mare Date: Thu, 17 Aug 2023 12:33:45 +1000 Subject: [PATCH 030/118] Fix an unbounded loop in the joystick code This fixes a bug introduced in b62a533 which, when a joystick was disabled and uncalibrated, caused unbounded recursive calls to Joystick::startPolling. --- src/Vehicle/Vehicle.cc | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 4fd1e1d520b..052e37c1e6f 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -2142,9 +2142,7 @@ void Vehicle::setJoystickEnabled(bool enabled) // if we are the active vehicle, call start polling on the active joystick // This routes the joystick signals to this vehicle - // We do this even if we are disabling the joystick - // because it will trigger disconnection of the signals - if (_toolbox->multiVehicleManager()->activeVehicle() == this){ + if (enabled && _toolbox->multiVehicleManager()->activeVehicle() == this){ _captureJoystick(); } From 345621601ba99a68cd4b9ae871f5b98eb20962d9 Mon Sep 17 00:00:00 2001 From: Sergii Lisovenko <2522054+s-lisovenko@users.noreply.github.com> Date: Fri, 4 Aug 2023 18:41:22 +0300 Subject: [PATCH 031/118] Add APMRemoteSupportComponent to CMake Lists This update modifies the CMakeLists.txt files in both the AutoPilotPlugins directory and within the APM subdirectory, adding APMRemoteSupportComponent to the list of components included in the project's build. This change is necessary to ensure that the new APMremoteSupportComponent is compiled when the project is built. --- src/AutoPilotPlugins/APM/CMakeLists.txt | 3 ++- src/AutoPilotPlugins/CMakeLists.txt | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/src/AutoPilotPlugins/APM/CMakeLists.txt b/src/AutoPilotPlugins/APM/CMakeLists.txt index 565e54157a1..8cd4709cd24 100644 --- a/src/AutoPilotPlugins/APM/CMakeLists.txt +++ b/src/AutoPilotPlugins/APM/CMakeLists.txt @@ -14,6 +14,7 @@ SOURCES APMPowerComponent.qml APMPowerComponentSummary.qml APMRadioComponentSummary.qml + APMRemoteSupportComponent.qml APMSafetyComponent.qml APMSafetyComponentCopter.qml APMSafetyComponentPlane.qml @@ -32,4 +33,4 @@ SOURCES APMTuningComponentCopter.qml APMTuningComponentSub.qml -) \ No newline at end of file +) diff --git a/src/AutoPilotPlugins/CMakeLists.txt b/src/AutoPilotPlugins/CMakeLists.txt index e737b81d8cb..5331d61ec78 100644 --- a/src/AutoPilotPlugins/CMakeLists.txt +++ b/src/AutoPilotPlugins/CMakeLists.txt @@ -18,6 +18,7 @@ add_library(AutoPilotPlugins APM/APMMotorComponent.cc APM/APMPowerComponent.cc APM/APMRadioComponent.cc + APM/APMRemoteSupportComponent.cc APM/APMSafetyComponent.cc APM/APMSensorsComponent.cc APM/APMSensorsComponentController.cc From 3840476213daf1ca057cead7e75db8845758b031 Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Thu, 17 Aug 2023 16:00:35 -0800 Subject: [PATCH 032/118] apply selected color to InstrumentValueLabel text --- src/QmlControls/InstrumentValueLabel.qml | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/QmlControls/InstrumentValueLabel.qml b/src/QmlControls/InstrumentValueLabel.qml index 49ebbf76dc4..7ec8b370d73 100644 --- a/src/QmlControls/InstrumentValueLabel.qml +++ b/src/QmlControls/InstrumentValueLabel.qml @@ -28,6 +28,7 @@ ColumnLayout { property var _rgFontSizeTightHeights: [ _tightDefaultFontHeight * _rgFontSizeRatios[0] + 2, _tightDefaultFontHeight * _rgFontSizeRatios[1] + 2, _tightDefaultFontHeight * _rgFontSizeRatios[2] + 2, _tightDefaultFontHeight * _rgFontSizeRatios[3] + 2 ] property real _tightHeight: _rgFontSizeTightHeights[instrumentValueData.factValueGrid.fontSize] property bool _iconVisible: instrumentValueData.rangeType === InstrumentValueData.IconSelectRange || instrumentValueData.icon + property var _color: instrumentValueData.isValidColor(instrumentValueData.currentColor) ? instrumentValueData.currentColor : qgcPal.text QGCPalette { id: qgcPal; colorGroupEnabled: enabled } @@ -40,7 +41,7 @@ ColumnLayout { fillMode: Image.PreserveAspectFit mipmap: true smooth: true - color: instrumentValueData.isValidColor(instrumentValueData.currentColor) ? instrumentValueData.currentColor : qgcPal.text + color: _color opacity: instrumentValueData.currentOpacity visible: _iconVisible @@ -77,6 +78,8 @@ ColumnLayout { height: _tightHeight font.pointSize: ScreenTools.smallFontPointSize text: instrumentValueData.text + color: _color + opacity: instrumentValueData.currentOpacity visible: !_iconVisible } } From faba9a788e88b4560f94b0ab953e0e9595a96878 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Mon, 21 Aug 2023 15:20:25 +0000 Subject: [PATCH 033/118] Update PX4 Firmware metadata Mon Aug 21 15:20:25 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index fb1cee5c4fe..89bfc15b2a5 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -1042,7 +1042,7 @@ Delay between failsafe condition triggered and failsafe reaction - Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode for the user to realize. During that time the user cannot take over control. Afterwards the configured failsafe action is triggered and the user may take over. A zero value disables the delay and the user cannot take over via stick movements (switching modes is still allowed). + Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode for the user to realize. During that time the user cannot take over control via the stick override feature see COM_RC_OVERRIDE. Afterwards the configured failsafe action is triggered and the user may use stick override. A zero value disables the delay and the user cannot take over via stick movements (switching modes is still allowed). 0.0 25.0 s From 0a357eb900dc34c83c89595f7f0b317f292a4524 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 22 Aug 2023 09:21:45 -0700 Subject: [PATCH 034/118] Revert "Support custom builds with joysticks which are buttons only" This reverts commit 48d1441493b3c193bbd2c5fc63c650bf2ae51e48. --- src/Joystick/Joystick.cc | 14 +++++--------- src/Joystick/Joystick.h | 5 ----- src/VehicleSetup/JoystickConfig.qml | 12 +----------- src/VehicleSetup/SetupView.qml | 2 +- src/api/QGCOptions.h | 4 ---- 5 files changed, 7 insertions(+), 30 deletions(-) diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index 3217d6b7461..7c03360a3d4 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -16,8 +16,6 @@ #include "VideoManager.h" #include "QGCCameraManager.h" #include "QGCCameraControl.h" -#include "QGCCorePlugin.h" -#include "QGCOptions.h" #include @@ -110,8 +108,6 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC , _totalButtonCount(_buttonCount+_hatButtonCount) , _multiVehicleManager(multiVehicleManager) { - _useButtonsOnly = qgcApp()->toolbox()->corePlugin()->options()->joystickUseButtonsOnly(); - qRegisterMetaType(); _rgAxisValues = new int[static_cast(_axisCount)]; @@ -728,9 +724,10 @@ void Joystick::startPolling(Vehicle* vehicle) } // Update qml in case of joystick transition emit calibratedChanged(_calibrated); + // Build action list _buildActionList(vehicle); - - if (vehicle->joystickEnabled() || _useButtonsOnly) { + // Only connect the new vehicle if it wants joystick data + if (vehicle->joystickEnabled()) { _pollingStartedForCalibration = false; connect(this, &Joystick::setArmed, _activeVehicle, &Vehicle::setArmedShowError); connect(this, &Joystick::setVtolInFwdFlight, _activeVehicle, &Vehicle::setVtolInFwdFlight); @@ -752,7 +749,7 @@ void Joystick::startPolling(Vehicle* vehicle) void Joystick::stopPolling(void) { if (isRunning()) { - if (_activeVehicle && (_activeVehicle->joystickEnabled() || _useButtonsOnly)) { + if (_activeVehicle && _activeVehicle->joystickEnabled()) { disconnect(this, &Joystick::setArmed, _activeVehicle, &Vehicle::setArmedShowError); disconnect(this, &Joystick::setVtolInFwdFlight, _activeVehicle, &Vehicle::setVtolInFwdFlight); disconnect(this, &Joystick::setFlightMode, _activeVehicle, &Vehicle::setFlightMode); @@ -999,10 +996,9 @@ void Joystick::setCalibrationMode(bool calibrating) void Joystick::_executeButtonAction(const QString& action, bool buttonDown) { - if (!_activeVehicle || (!_activeVehicle->joystickEnabled() && !_useButtonsOnly) || action == _buttonActionNone) { + if (!_activeVehicle || !_activeVehicle->joystickEnabled() || action == _buttonActionNone) { return; } - if (action == _buttonActionArm) { if (buttonDown) emit setArmed(true); } else if (action == _buttonActionDisarm) { diff --git a/src/Joystick/Joystick.h b/src/Joystick/Joystick.h index d791f1ed25e..2c6f2893d8b 100644 --- a/src/Joystick/Joystick.h +++ b/src/Joystick/Joystick.h @@ -94,10 +94,6 @@ class Joystick : public QThread Q_PROPERTY(int axisCount READ axisCount CONSTANT) Q_PROPERTY(bool requiresCalibration READ requiresCalibration CONSTANT) - // This property is used to indicate a joystick setup where the stick axes are ignored and only the - // buttons are supported. This type of setup is used by a Herelink controller for example. - Q_PROPERTY(bool useButtonsOnly MEMBER _useButtonsOnly CONSTANT) - //-- Actions assigned to buttons Q_PROPERTY(QStringList buttonActions READ buttonActions NOTIFY buttonActionsChanged) @@ -279,7 +275,6 @@ class Joystick : public QThread std::atomic _exitThread{false}; ///< true: signal thread to exit bool _calibrationMode = false; - bool _useButtonsOnly = false; int* _rgAxisValues = nullptr; Calibration_t* _rgCalibration = nullptr; ThrottleMode_t _throttleMode = ThrottleModeDownZero; diff --git a/src/VehicleSetup/JoystickConfig.qml b/src/VehicleSetup/JoystickConfig.qml index 2c744ab615f..3ba6e90b67e 100644 --- a/src/VehicleSetup/JoystickConfig.qml +++ b/src/VehicleSetup/JoystickConfig.qml @@ -62,30 +62,20 @@ SetupPage { id: bar width: parent.width Component.onCompleted: { - currentIndex = 0 - if (_activeJoystick) { - if (_activeJoystick.useButtonsOnly) { - currentIndex = 1 - } else if (_activeJoystick.calibrated) { - currentIndex = 2 - } - } + currentIndex = _activeJoystick && _activeJoystick.calibrated ? 0 : 2 } anchors.top: parent.top QGCTabButton { text: qsTr("General") - visible: !_activeJoystick.useButtonsOnly } QGCTabButton { text: qsTr("Button Assigment") } QGCTabButton { text: qsTr("Calibration") - visible: !_activeJoystick.useButtonsOnly } QGCTabButton { text: qsTr("Advanced") - visible: !_activeJoystick.useButtonsOnly } } diff --git a/src/VehicleSetup/SetupView.qml b/src/VehicleSetup/SetupView.qml index 012aebd32ef..70946d1edc2 100644 --- a/src/VehicleSetup/SetupView.qml +++ b/src/VehicleSetup/SetupView.qml @@ -260,7 +260,7 @@ Rectangle { id: joystickButton imageResource: "/qmlimages/Joystick.png" setupIndicator: true - setupComplete: joystickManager.activeJoystick ? (joystickManager.activeJoystick.calibrated || joystickManager.activeJoystick.useButtonsOnly) : false + setupComplete: joystickManager.activeJoystick ? joystickManager.activeJoystick.calibrated : false exclusiveGroup: setupButtonGroup visible: _fullParameterVehicleAvailable && joystickManager.joysticks.length !== 0 text: qsTr("Joystick") diff --git a/src/api/QGCOptions.h b/src/api/QGCOptions.h index e796dbfb3d0..43f01167d0c 100644 --- a/src/api/QGCOptions.h +++ b/src/api/QGCOptions.h @@ -146,10 +146,6 @@ class QGCOptions : public QObject virtual QGCFlyViewOptions* flyViewOptions (); - // This is used to indicate a joystick setup where the stick axes are ignored and only the - // buttons are supported. This type of setup is used by a Herelink controller for example. - virtual bool joystickUseButtonsOnly() const { return false; } - signals: void showSensorCalibrationCompassChanged (bool show); void showSensorCalibrationGyroChanged (bool show); From 41d651bdabfd85ebab1cd214a0fa6286440e602c Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 22 Aug 2023 17:05:38 +0000 Subject: [PATCH 035/118] Revert deleted functionality --- src/Vehicle/Vehicle.cc | 14 ++------------ 1 file changed, 2 insertions(+), 12 deletions(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 052e37c1e6f..1813d7ac998 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -2088,21 +2088,11 @@ void Vehicle::_loadJoystickSettings() { QSettings settings; settings.beginGroup(QString(_settingsGroup).arg(_id)); - const bool _useButtonsOnly = qgcApp()->toolbox()->corePlugin()->options()->joystickUseButtonsOnly(); - if (!_useButtonsOnly && _toolbox->joystickManager()->activeJoystick()) { + if (_toolbox->joystickManager()->activeJoystick()) { qCDebug(JoystickLog) << "Vehicle " << this->id() << " Notified of an active joystick. Loading setting joystickenabled: " << settings.value(_joystickEnabledSettingsKey, false).toBool(); setJoystickEnabled(settings.value(_joystickEnabledSettingsKey, false).toBool()); - } - else if(_useButtonsOnly) - { - // in a build with _useButtonsOnly set, joystickenable should always be left false - // this prevents the sticks from doing anything - qCDebug(JoystickLog) << "Vehicle " << this->id() << " Skipping Load of Joystick Settings because QCC Options useButtonsOnly is set"; - setJoystickEnabled(false); - } - else - { + } else { qCDebug(JoystickLog) << "Vehicle " << this->id() << " Notified that there is no active joystick"; setJoystickEnabled(false); } From cb39702cc6ba729333d139c1bd6047255de11d76 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 24 Aug 2023 13:45:04 +0200 Subject: [PATCH 036/118] mavlink: update submodule --- libs/mavlink/include/mavlink/v2.0 | 2 +- src/AutoPilotPlugins/PX4/PX4FlightBehavior.cc | 2 +- src/AutoPilotPlugins/PX4/PX4TuningComponent.cc | 2 +- src/FirmwarePlugin/APM/APMFirmwarePlugin.cc | 4 ++-- src/FirmwarePlugin/APM/APMFirmwarePluginFactory.cc | 2 +- src/FirmwarePlugin/APM/APMParameterMetaData.cc | 2 +- src/Vehicle/RemoteIDManager.cc | 4 ++-- src/Vehicle/Vehicle.cc | 4 ++-- src/comm/QGCMAVLink.cc | 2 +- 9 files changed, 12 insertions(+), 12 deletions(-) diff --git a/libs/mavlink/include/mavlink/v2.0 b/libs/mavlink/include/mavlink/v2.0 index 97c50e12876..55988d1ec99 160000 --- a/libs/mavlink/include/mavlink/v2.0 +++ b/libs/mavlink/include/mavlink/v2.0 @@ -1 +1 @@ -Subproject commit 97c50e128768c9b95c5542b8fc751198b1af96da +Subproject commit 55988d1ec99761b9c5e447a51dcb258161672805 diff --git a/src/AutoPilotPlugins/PX4/PX4FlightBehavior.cc b/src/AutoPilotPlugins/PX4/PX4FlightBehavior.cc index 1a852e80466..3cd44b3b9de 100644 --- a/src/AutoPilotPlugins/PX4/PX4FlightBehavior.cc +++ b/src/AutoPilotPlugins/PX4/PX4FlightBehavior.cc @@ -69,7 +69,7 @@ QUrl PX4FlightBehavior::setupSource() const case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: qmlFile = ""; break; diff --git a/src/AutoPilotPlugins/PX4/PX4TuningComponent.cc b/src/AutoPilotPlugins/PX4/PX4TuningComponent.cc index 53c9eae178e..ec315d5687c 100644 --- a/src/AutoPilotPlugins/PX4/PX4TuningComponent.cc +++ b/src/AutoPilotPlugins/PX4/PX4TuningComponent.cc @@ -69,7 +69,7 @@ QUrl PX4TuningComponent::setupSource(void) const case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: qmlFile = "qrc:/qml/PX4TuningComponentVTOL.qml"; break; diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index d404c70b7f9..185a521cf9f 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -476,7 +476,7 @@ void APMFirmwarePlugin::initializeVehicle(Vehicle* vehicle) case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: case MAV_TYPE_FIXED_WING: vehicle->setFirmwareVersion(3, 9, 0); @@ -699,7 +699,7 @@ QString APMFirmwarePlugin::_internalParameterMetaDataFile(Vehicle* vehicle) case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: case MAV_TYPE_FIXED_WING: if (vehicle->versionCompare(4, 2, 0) >= 0) { diff --git a/src/FirmwarePlugin/APM/APMFirmwarePluginFactory.cc b/src/FirmwarePlugin/APM/APMFirmwarePluginFactory.cc index 7f2cdef3c86..d6b9f1f4a50 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePluginFactory.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePluginFactory.cc @@ -51,7 +51,7 @@ FirmwarePlugin* APMFirmwarePluginFactory::firmwarePluginForAutopilot(MAV_AUTOPIL case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: case MAV_TYPE_FIXED_WING: if (!_arduPlanePluginInstance) { diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.cc b/src/FirmwarePlugin/APM/APMParameterMetaData.cc index 78d23cc310a..4ad005546e1 100644 --- a/src/FirmwarePlugin/APM/APMParameterMetaData.cc +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.cc @@ -90,7 +90,7 @@ QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum) case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: vehicleName = "ArduPlane"; break; diff --git a/src/Vehicle/RemoteIDManager.cc b/src/Vehicle/RemoteIDManager.cc index 11ad0f30c72..f88fc3a92ee 100644 --- a/src/Vehicle/RemoteIDManager.cc +++ b/src/Vehicle/RemoteIDManager.cc @@ -126,7 +126,7 @@ void RemoteIDManager::_handleArmStatus(mavlink_message_t& message) mavlink_open_drone_id_arm_status_t armStatus; mavlink_msg_open_drone_id_arm_status_decode(&message, &armStatus); - if (armStatus.status == MAV_ODID_GOOD_TO_ARM && !_armStatusGood) { + if (armStatus.status == MAV_ODID_ARM_STATUS_GOOD_TO_ARM && !_armStatusGood) { // If good to arm, even if basic ID is not set on GCS, it was set by remoteID parameters, so GCS one would be optional in this case if (!_basicIDGood) { _basicIDGood = true; @@ -137,7 +137,7 @@ void RemoteIDManager::_handleArmStatus(mavlink_message_t& message) qCDebug(RemoteIDManagerLog) << "Arm status GOOD TO ARM."; } - if (armStatus.status == MAV_ODID_PRE_ARM_FAIL_GENERIC) { + if (armStatus.status == MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC) { _armStatusGood = false; _armStatusError = QString::fromLocal8Bit(armStatus.error); // Check if the error is because of missing basic id diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 1813d7ac998..91280aac31e 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -2570,14 +2570,14 @@ QString Vehicle::vehicleTypeName() const { { MAV_TYPE_OCTOROTOR, tr("Octorotor")}, { MAV_TYPE_TRICOPTER, tr("Octorotor")}, { MAV_TYPE_FLAPPING_WING, tr("Flapping wing")}, - { MAV_TYPE_KITE, tr("Flapping wing")}, + { MAV_TYPE_KITE, tr("Kite")}, { MAV_TYPE_ONBOARD_CONTROLLER, tr("Onboard companion controller")}, { MAV_TYPE_VTOL_TAILSITTER_DUOROTOR, tr("Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter")}, { MAV_TYPE_VTOL_TAILSITTER_QUADROTOR, tr("Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter")}, { MAV_TYPE_VTOL_TILTROTOR, tr("Tiltrotor VTOL")}, { MAV_TYPE_VTOL_FIXEDROTOR, tr("VTOL Fixedrotor")}, { MAV_TYPE_VTOL_TAILSITTER, tr("VTOL Tailsitter")}, - { MAV_TYPE_VTOL_RESERVED4, tr("VTOL reserved 4")}, + { MAV_TYPE_VTOL_TILTWING, tr("VTOL Tiltwing")}, { MAV_TYPE_VTOL_RESERVED5, tr("VTOL reserved 5")}, { MAV_TYPE_GIMBAL, tr("Onboard gimbal")}, { MAV_TYPE_ADSB, tr("Onboard ADSB peripheral")}, diff --git a/src/comm/QGCMAVLink.cc b/src/comm/QGCMAVLink.cc index 59f9240bf87..2f20bc2fa61 100644 --- a/src/comm/QGCMAVLink.cc +++ b/src/comm/QGCMAVLink.cc @@ -130,7 +130,7 @@ QGCMAVLink::VehicleClass_t QGCMAVLink::vehicleClass(MAV_TYPE mavType) case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: return VehicleClassVTOL; case MAV_TYPE_FIXED_WING: From c716fbb28383df9984f9efd84c70e6fb39390d28 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 24 Aug 2023 13:46:02 +0200 Subject: [PATCH 037/118] QGCExternalLibs.pri: switch to all mavlink dialect by default This allows to use messages from development.xml --- QGCExternalLibs.pri | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/QGCExternalLibs.pri b/QGCExternalLibs.pri index 2d3422c66dd..df313799041 100644 --- a/QGCExternalLibs.pri +++ b/QGCExternalLibs.pri @@ -54,7 +54,7 @@ isEmpty(MAVLINK_CONF) { MAVLINK_CONF = $$fromfile(user_config.pri, MAVLINK_CONF) message($$sprintf("Using user-supplied mavlink dialect '%1' specified in user_config.pri", $$MAVLINK_CONF)) } else { - MAVLINK_CONF = ardupilotmega + MAVLINK_CONF = all } } From 9478bcecf2f7233b354010660d11762f3b509990 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 24 Aug 2023 18:07:02 +0200 Subject: [PATCH 038/118] FirmwareUpgradeController: remove unuse variables & use https for firmware.ardupilot.org --- src/VehicleSetup/FirmwareUpgradeController.cc | 4 +--- src/VehicleSetup/FirmwareUpgradeController.h | 3 --- 2 files changed, 1 insertion(+), 6 deletions(-) diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/VehicleSetup/FirmwareUpgradeController.cc index 747589ff599..303a9086603 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.cc +++ b/src/VehicleSetup/FirmwareUpgradeController.cc @@ -109,8 +109,6 @@ FirmwareUpgradeController::FirmwareUpgradeController(void) : _singleFirmwareURL (qgcApp()->toolbox()->corePlugin()->options()->firmwareUpgradeSingleURL()) , _singleFirmwareMode (!_singleFirmwareURL.isEmpty()) , _downloadingFirmwareList (false) - , _downloadManager (nullptr) - , _downloadNetworkReply (nullptr) , _statusLog (nullptr) , _selectedFirmwareBuildType (StableFirmware) , _image (nullptr) @@ -688,7 +686,7 @@ void FirmwareUpgradeController::_downloadArduPilotManifest(void) QGCFileDownload* downloader = new QGCFileDownload(this); connect(downloader, &QGCFileDownload::downloadComplete, this, &FirmwareUpgradeController::_ardupilotManifestDownloadComplete); - downloader->download(QStringLiteral("http://firmware.ardupilot.org/manifest.json.gz")); + downloader->download(QStringLiteral("https://firmware.ardupilot.org/manifest.json.gz")); } void FirmwareUpgradeController::_ardupilotManifestDownloadComplete(QString remoteFile, QString localFile, QString errorMsg) diff --git a/src/VehicleSetup/FirmwareUpgradeController.h b/src/VehicleSetup/FirmwareUpgradeController.h index 90ebb500ca5..abd99b06ef0 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.h +++ b/src/VehicleSetup/FirmwareUpgradeController.h @@ -226,9 +226,6 @@ private slots: QString _firmwareFilename; ///< Image which we are going to flash to the board - QNetworkAccessManager* _downloadManager; ///< Used for firmware file downloading across the internet - QNetworkReply* _downloadNetworkReply; ///< Used for firmware file downloading across the internet - /// @brief Thread controller which is used to run bootloader commands on separate thread PX4FirmwareUpgradeThreadController* _threadController; From 81dea5ace65a8a979ab472a76083adadd4d36967 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 24 Aug 2023 18:07:52 +0200 Subject: [PATCH 039/118] QGCFileDownload: handle OpenSSL build time vs runtime version mismatch --- src/QGCFileDownload.cc | 18 ++++++++++++++++++ src/QGCFileDownload.h | 2 ++ src/QtLocationPlugin/QGCMapTileSet.cpp | 2 ++ src/Terrain/TerrainQuery.cc | 3 ++- 4 files changed, 24 insertions(+), 1 deletion(-) diff --git a/src/QGCFileDownload.cc b/src/QGCFileDownload.cc index c5921e6c6b6..e67da07af88 100644 --- a/src/QGCFileDownload.cc +++ b/src/QGCFileDownload.cc @@ -60,6 +60,8 @@ bool QGCFileDownload::download(const QString& remoteFile, const QVector errorsThatCanBeIgnored; + errorsThatCanBeIgnored << QSslError(QSslError::NoPeerCertificate); + networkReply.ignoreSslErrors(errorsThatCanBeIgnored); + } +} diff --git a/src/QGCFileDownload.h b/src/QGCFileDownload.h index b4e0c516942..3c9932a505a 100644 --- a/src/QGCFileDownload.h +++ b/src/QGCFileDownload.h @@ -25,6 +25,8 @@ class QGCFileDownload : public QNetworkAccessManager /// @return true: Asynchronous download has started, false: Download initialization failed bool download(const QString& remoteFile, const QVector>& requestAttributes={}, bool redirect = false); + static void setIgnoreSSLErrorsIfNeeded(QNetworkReply& networkReply); + signals: void downloadProgress(qint64 curr, qint64 total); void downloadComplete(QString remoteFile, QString localFile, QString errorMsg); diff --git a/src/QtLocationPlugin/QGCMapTileSet.cpp b/src/QtLocationPlugin/QGCMapTileSet.cpp index e8ad05d1afb..4c21eeb54fd 100644 --- a/src/QtLocationPlugin/QGCMapTileSet.cpp +++ b/src/QtLocationPlugin/QGCMapTileSet.cpp @@ -19,6 +19,7 @@ #include "QGCMapEngine.h" #include "QGCMapTileSet.h" #include "QGCMapEngineManager.h" +#include "QGCFileDownload.h" #include "TerrainTile.h" #include @@ -249,6 +250,7 @@ void QGCCachedTileSet::_prepareDownload() #endif QNetworkReply* reply = _networkManager->get(request); reply->setParent(0); + QGCFileDownload::setIgnoreSSLErrorsIfNeeded(*reply); connect(reply, &QNetworkReply::finished, this, &QGCCachedTileSet::_networkReplyFinished); connect(reply, &QNetworkReply::errorOccurred, this, &QGCCachedTileSet::_networkReplyError); _replies.insert(tile->hash(), reply); diff --git a/src/Terrain/TerrainQuery.cc b/src/Terrain/TerrainQuery.cc index 8e32d005fd6..10456c32481 100644 --- a/src/Terrain/TerrainQuery.cc +++ b/src/Terrain/TerrainQuery.cc @@ -10,6 +10,7 @@ #include "TerrainQuery.h" #include "QGCMapEngine.h" #include "QGeoMapReplyQGC.h" +#include "QGCFileDownload.h" #include "QGCApplication.h" #include @@ -123,7 +124,7 @@ void TerrainAirMapQuery::_sendQuery(const QString& path, const QUrlQuery& urlQue _requestFailed(); return; } - networkReply->ignoreSslErrors(); + QGCFileDownload::setIgnoreSSLErrorsIfNeeded(*networkReply); connect(networkReply, &QNetworkReply::finished, this, &TerrainAirMapQuery::_requestFinished); connect(networkReply, &QNetworkReply::sslErrors, this, &TerrainAirMapQuery::_sslErrors); From d0c61b2f79473db9e2438180ebea9e8e2cce686d Mon Sep 17 00:00:00 2001 From: leonardosimovic Date: Wed, 26 Jul 2023 09:54:10 +0200 Subject: [PATCH 040/118] perf(MapEngine): avoid some unnecessary string copies --- src/QtLocationPlugin/QGCMapEngine.cpp | 12 ++++++------ src/QtLocationPlugin/QGCMapEngine.h | 16 ++++++++-------- src/QtLocationPlugin/QGCMapEngineData.h | 2 +- src/QtLocationPlugin/QGCMapUrlEngine.cpp | 19 ++++++++++++------- src/QtLocationPlugin/QGCMapUrlEngine.h | 14 +++++++------- src/QtLocationPlugin/QGCTileCacheWorker.cpp | 6 +++--- 6 files changed, 37 insertions(+), 32 deletions(-) diff --git a/src/QtLocationPlugin/QGCMapEngine.cpp b/src/QtLocationPlugin/QGCMapEngine.cpp index 15774db3683..6f29fc64571 100644 --- a/src/QtLocationPlugin/QGCMapEngine.cpp +++ b/src/QtLocationPlugin/QGCMapEngine.cpp @@ -200,7 +200,7 @@ QGCMapEngine::addTask(QGCMapTask* task) //----------------------------------------------------------------------------- void -QGCMapEngine::cacheTile(QString type, int x, int y, int z, const QByteArray& image, const QString &format, qulonglong set) +QGCMapEngine::cacheTile(const QString& type, int x, int y, int z, const QByteArray& image, const QString &format, qulonglong set) { QString hash = getTileHash(type, x, y, z); cacheTile(type, hash, image, format, set); @@ -208,7 +208,7 @@ QGCMapEngine::cacheTile(QString type, int x, int y, int z, const QByteArray& ima //----------------------------------------------------------------------------- void -QGCMapEngine::cacheTile(QString type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set) +QGCMapEngine::cacheTile(const QString& type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set) { AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings(); //-- If we are allowed to persist data, save tile to cache @@ -220,7 +220,7 @@ QGCMapEngine::cacheTile(QString type, const QString& hash, const QByteArray& ima //----------------------------------------------------------------------------- QString -QGCMapEngine::getTileHash(QString type, int x, int y, int z) +QGCMapEngine::getTileHash(const QString& type, int x, int y, int z) { return QString::asprintf("%010d%08d%08d%03d", getQGCMapEngine()->urlFactory()->getIdFromType(type), x, y, z); } @@ -235,7 +235,7 @@ QGCMapEngine::hashToType(const QString& hash) //----------------------------------------------------------------------------- QGCFetchTileTask* -QGCMapEngine::createFetchTileTask(QString type, int x, int y, int z) +QGCMapEngine::createFetchTileTask(const QString& type, int x, int y, int z) { QString hash = getTileHash(type, x, y, z); QGCFetchTileTask* task = new QGCFetchTileTask(hash); @@ -244,7 +244,7 @@ QGCMapEngine::createFetchTileTask(QString type, int x, int y, int z) //----------------------------------------------------------------------------- QGCTileSet -QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, QString mapType) +QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, const QString& mapType) { if(zoom < 1) zoom = 1; if(zoom > MAX_MAP_ZOOM) zoom = MAX_MAP_ZOOM; @@ -368,7 +368,7 @@ QGCMapEngine::_pruned() //----------------------------------------------------------------------------- int -QGCMapEngine::concurrentDownloads(QString type) +QGCMapEngine::concurrentDownloads(const QString& type) { Q_UNUSED(type); // TODO : We may want different values depending on diff --git a/src/QtLocationPlugin/QGCMapEngine.h b/src/QtLocationPlugin/QGCMapEngine.h index 4f4668d64c4..5f8bce7f2c1 100644 --- a/src/QtLocationPlugin/QGCMapEngine.h +++ b/src/QtLocationPlugin/QGCMapEngine.h @@ -36,13 +36,13 @@ class QGCMapEngine : public QObject void init (); void addTask (QGCMapTask *task); - void cacheTile (QString type, int x, int y, int z, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX); - void cacheTile (QString type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX); - QGCFetchTileTask* createFetchTileTask (QString type, int x, int y, int z); + void cacheTile (const QString& type, int x, int y, int z, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX); + void cacheTile (const QString& type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX); + QGCFetchTileTask* createFetchTileTask (const QString& type, int x, int y, int z); QStringList getMapNameList (); const QString userAgent () { return _userAgent; } void setUserAgent (const QString& ua) { _userAgent = ua; } - QString hashToType (const QString& hash); + QString hashToType (const QString& hash); quint32 getMaxDiskCache (); void setMaxDiskCache (quint32 size); quint32 getMaxMemCache (); @@ -56,13 +56,13 @@ class QGCMapEngine : public QObject UrlFactory* urlFactory () { return _urlFactory; } //-- Tile Math - static QGCTileSet getTileCount (int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, QString mapType); - static QString getTileHash (QString type, int x, int y, int z); - static QString getTypeFromName (const QString &name); + static QGCTileSet getTileCount (int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, const QString& mapType); + static QString getTileHash (const QString& type, int x, int y, int z); + static QString getTypeFromName (const QString& name); static QString bigSizeToString (quint64 size); static QString storageFreeSizeToString(quint64 size_MB); static QString numberToString (quint64 number); - static int concurrentDownloads (QString type); + static int concurrentDownloads (const QString& type); private slots: void _updateTotals (quint32 totaltiles, quint64 totalsize, quint32 defaulttiles, quint64 defaultsize); diff --git a/src/QtLocationPlugin/QGCMapEngineData.h b/src/QtLocationPlugin/QGCMapEngineData.h index 64cdbc14468..14fe489e3cb 100644 --- a/src/QtLocationPlugin/QGCMapEngineData.h +++ b/src/QtLocationPlugin/QGCMapEngineData.h @@ -76,7 +76,7 @@ class QGCCacheTile : public QObject { Q_OBJECT public: - QGCCacheTile (const QString hash, const QByteArray img, const QString format, QString type, qulonglong set = UINT64_MAX) + QGCCacheTile (const QString& hash, const QByteArray& img, const QString& format, const QString& type, qulonglong set = UINT64_MAX) : _set(set) , _hash(hash) , _img(img) diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.cpp b/src/QtLocationPlugin/QGCMapUrlEngine.cpp index 24edbda93fc..3e076255f20 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.cpp +++ b/src/QtLocationPlugin/QGCMapUrlEngine.cpp @@ -106,7 +106,7 @@ QString UrlFactory::getImageFormat(int id, const QByteArray& image) { } //----------------------------------------------------------------------------- -QString UrlFactory::getImageFormat(QString type, const QByteArray& image) { +QString UrlFactory::getImageFormat(const QString& type, const QByteArray& image) { if (_providersTable.find(type) != _providersTable.end()) { return _providersTable[type]->getImageFormat(image); } else { @@ -127,7 +127,7 @@ QNetworkRequest UrlFactory::getTileURL(int id, int x, int y, int zoom, } //----------------------------------------------------------------------------- -QNetworkRequest UrlFactory::getTileURL(QString type, int x, int y, int zoom, +QNetworkRequest UrlFactory::getTileURL(const QString& type, int x, int y, int zoom, QNetworkAccessManager* networkManager) { if (_providersTable.find(type) != _providersTable.end()) { return _providersTable[type]->getTileURL(x, y, zoom, networkManager); @@ -137,7 +137,7 @@ QNetworkRequest UrlFactory::getTileURL(QString type, int x, int y, int zoom, } //----------------------------------------------------------------------------- -quint32 UrlFactory::averageSizeForType(QString type) { +quint32 UrlFactory::averageSizeForType(const QString& type) { if (_providersTable.find(type) != _providersTable.end()) { return _providersTable[type]->getAverageSize(); } @@ -177,21 +177,26 @@ MapProvider* UrlFactory::getMapProviderFromId(int id) return nullptr; } +//----------------------------------------------------------------------------- // Todo : qHash produce a uint bigger than max(int) // There is still a low probability for this to // generate similar hash for different types -int UrlFactory::getIdFromType(QString type) { return (int)(qHash(type)>>1); } +int +UrlFactory::getIdFromType(const QString& type) +{ + return (int)(qHash(type)>>1); +} //----------------------------------------------------------------------------- int -UrlFactory::long2tileX(QString mapType, double lon, int z) +UrlFactory::long2tileX(const QString& mapType, double lon, int z) { return _providersTable[mapType]->long2tileX(lon, z); } //----------------------------------------------------------------------------- int -UrlFactory::lat2tileY(QString mapType, double lat, int z) +UrlFactory::lat2tileY(const QString& mapType, double lat, int z) { return _providersTable[mapType]->lat2tileY(lat, z); } @@ -199,7 +204,7 @@ UrlFactory::lat2tileY(QString mapType, double lat, int z) //----------------------------------------------------------------------------- QGCTileSet -UrlFactory::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, QString mapType) +UrlFactory::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, const QString& mapType) { return _providersTable[mapType]->getTileCount(zoom, topleftLon, topleftLat, bottomRightLon, bottomRightLat); } diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.h b/src/QtLocationPlugin/QGCMapUrlEngine.h index 898cf474704..6179fd4fa0d 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.h +++ b/src/QtLocationPlugin/QGCMapUrlEngine.h @@ -33,26 +33,26 @@ class UrlFactory : public QObject { UrlFactory (); ~UrlFactory (); - QNetworkRequest getTileURL (QString type, int x, int y, int zoom, QNetworkAccessManager* networkManager); + QNetworkRequest getTileURL (const QString& type, int x, int y, int zoom, QNetworkAccessManager* networkManager); QNetworkRequest getTileURL (int id, int x, int y, int zoom, QNetworkAccessManager* networkManager); - QString getImageFormat (QString type, const QByteArray& image); + QString getImageFormat (const QString& type, const QByteArray& image); QString getImageFormat (int id , const QByteArray& image); - quint32 averageSizeForType (QString type); + quint32 averageSizeForType (const QString& type); - int long2tileX(QString mapType, double lon, int z); - int lat2tileY(QString mapType, double lat, int z); + int long2tileX(const QString& mapType, double lon, int z); + int lat2tileY(const QString& mapType, double lat, int z); QHash getProviderTable(){return _providersTable;} - int getIdFromType(QString type); + int getIdFromType(const QString& type); QString getTypeFromId(int id); MapProvider* getMapProviderFromId(int id); QGCTileSet getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, - QString mapType); + const QString& mapType); bool isElevation(int mapId); diff --git a/src/QtLocationPlugin/QGCTileCacheWorker.cpp b/src/QtLocationPlugin/QGCTileCacheWorker.cpp index 1540bc8fc7f..f8f918876d8 100644 --- a/src/QtLocationPlugin/QGCTileCacheWorker.cpp +++ b/src/QtLocationPlugin/QGCTileCacheWorker.cpp @@ -329,11 +329,11 @@ QGCCacheWorker::_getTile(QGCMapTask* mtask) QString s = QString("SELECT tile, format, type FROM Tiles WHERE hash = \"%1\"").arg(task->hash()); if(query.exec(s)) { if(query.next()) { - QByteArray ar = query.value(0).toByteArray(); - QString format = query.value(1).toString(); + const QByteArray& arrray = query.value(0).toByteArray(); + const QString& format = query.value(1).toString(); QString type = getQGCMapEngine()->urlFactory()->getTypeFromId(query.value(2).toInt()); qCDebug(QGCTileCacheLog) << "_getTile() (Found in DB) HASH:" << task->hash(); - QGCCacheTile* tile = new QGCCacheTile(task->hash(), ar, format, type); + QGCCacheTile* tile = new QGCCacheTile(task->hash(), arrray, format, type); task->setTileFetched(tile); found = true; } From e7b790815224d22c06e115acd2e49089ba93ff2d Mon Sep 17 00:00:00 2001 From: leonardosimovic Date: Thu, 20 Jul 2023 15:39:01 +0200 Subject: [PATCH 041/118] feat: replace airmap terrain with copernicus --- src/QmlControls/QGroundControlQmlGlobal.h | 6 + src/QtLocationPlugin/ElevationMapProvider.cpp | 20 +- src/QtLocationPlugin/ElevationMapProvider.h | 5 +- src/QtLocationPlugin/QGCMapTileSet.cpp | 2 +- src/QtLocationPlugin/QGCMapUrlEngine.cpp | 4 +- src/QtLocationPlugin/QGCMapUrlEngine.h | 1 + .../QMLControl/OfflineMap.qml | 2 +- .../QMLControl/QGCMapEngineManager.cc | 10 +- src/Terrain/TerrainQuery.cc | 24 +- src/TerrainTile.cc | 252 ++++++++---------- src/TerrainTile.h | 27 +- 11 files changed, 171 insertions(+), 182 deletions(-) diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h index f613e3b5f8b..ff17e4452d0 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.h +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -106,6 +106,10 @@ class QGroundControlQmlGlobal : public QGCTool Q_PROPERTY(bool hasMAVLinkInspector READ hasMAVLinkInspector CONSTANT) + //------------------------------------------------------------------------- + // Elevation Provider + Q_PROPERTY(QString elevationProviderName READ elevationProviderName CONSTANT) + #if defined(QGC_ENABLE_PAIRING) Q_PROPERTY(PairingManager* pairingManager READ pairingManager CONSTANT) #endif @@ -203,6 +207,8 @@ class QGroundControlQmlGlobal : public QGCTool bool hasMAVLinkInspector () { return true; } #endif + QString elevationProviderName () { return UrlFactory::kCopernicusElevationProviderKey; } + bool singleFirmwareSupport (); bool singleVehicleSupport (); bool px4ProFirmwareSupported (); diff --git a/src/QtLocationPlugin/ElevationMapProvider.cpp b/src/QtLocationPlugin/ElevationMapProvider.cpp index c362464b503..851f162eca6 100644 --- a/src/QtLocationPlugin/ElevationMapProvider.cpp +++ b/src/QtLocationPlugin/ElevationMapProvider.cpp @@ -6,32 +6,40 @@ #include "QGCMapEngine.h" #include "TerrainTile.h" +/* +License for the COPERNICUS dataset hosted on https://terrain-ce.suite.auterion.com/: + +© DLR e.V. 2010-2014 and © Airbus Defence and Space GmbH 2014-2018 provided under COPERNICUS +by the European Union and ESA; all rights reserved. + +*/ + ElevationProvider::ElevationProvider(const QString& imageFormat, quint32 averageSize, QGeoMapType::MapStyle mapType, QObject* parent) - : MapProvider(QStringLiteral("https://api.airmap.com/"), imageFormat, averageSize, mapType, parent) {} + : MapProvider(QStringLiteral("https://terrain-ce.suite.auterion.com/"), imageFormat, averageSize, mapType, parent) {} //----------------------------------------------------------------------------- -int AirmapElevationProvider::long2tileX(const double lon, const int z) const { +int CopernicusElevationProvider::long2tileX(const double lon, const int z) const { Q_UNUSED(z) return static_cast(floor((lon + 180.0) / TerrainTile::tileSizeDegrees)); } //----------------------------------------------------------------------------- -int AirmapElevationProvider::lat2tileY(const double lat, const int z) const { +int CopernicusElevationProvider::lat2tileY(const double lat, const int z) const { Q_UNUSED(z) return static_cast(floor((lat + 90.0) / TerrainTile::tileSizeDegrees)); } -QString AirmapElevationProvider::_getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) { +QString CopernicusElevationProvider::_getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) { Q_UNUSED(networkManager) Q_UNUSED(zoom) - return QString("https://api.airmap.com/elevation/v1/ele/carpet?points=%1,%2,%3,%4") + return QString("https://terrain-ce.suite.auterion.com/api/v1/carpet?points=%1,%2,%3,%4") .arg(static_cast(y) * TerrainTile::tileSizeDegrees - 90.0) .arg(static_cast(x) * TerrainTile::tileSizeDegrees - 180.0) .arg(static_cast(y + 1) * TerrainTile::tileSizeDegrees - 90.0) .arg(static_cast(x + 1) * TerrainTile::tileSizeDegrees - 180.0); } -QGCTileSet AirmapElevationProvider::getTileCount(const int zoom, const double topleftLon, +QGCTileSet CopernicusElevationProvider::getTileCount(const int zoom, const double topleftLon, const double topleftLat, const double bottomRightLon, const double bottomRightLat) const { QGCTileSet set; diff --git a/src/QtLocationPlugin/ElevationMapProvider.h b/src/QtLocationPlugin/ElevationMapProvider.h index ce2cbea7345..842056918ac 100644 --- a/src/QtLocationPlugin/ElevationMapProvider.h +++ b/src/QtLocationPlugin/ElevationMapProvider.h @@ -24,10 +24,10 @@ class ElevationProvider : public MapProvider { // ----------------------------------------------------------- // Airmap Elevation -class AirmapElevationProvider : public ElevationProvider { +class CopernicusElevationProvider : public ElevationProvider { Q_OBJECT public: - AirmapElevationProvider(QObject* parent = nullptr) + CopernicusElevationProvider(QObject* parent = nullptr) : ElevationProvider(QStringLiteral("bin"), AVERAGE_AIRMAP_ELEV_SIZE, QGeoMapType::StreetMap, parent) {} @@ -42,4 +42,3 @@ class AirmapElevationProvider : public ElevationProvider { protected: QString _getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) override; }; - diff --git a/src/QtLocationPlugin/QGCMapTileSet.cpp b/src/QtLocationPlugin/QGCMapTileSet.cpp index 4c21eeb54fd..5888cad887f 100644 --- a/src/QtLocationPlugin/QGCMapTileSet.cpp +++ b/src/QtLocationPlugin/QGCMapTileSet.cpp @@ -289,7 +289,7 @@ QGCCachedTileSet::_networkReplyFinished() qCDebug(QGCCachedTileSetLog) << "Tile fetched" << hash; QByteArray image = reply->readAll(); QString type = getQGCMapEngine()->hashToType(hash); - if (type == "Airmap Elevation" ) { + if (type == UrlFactory::kCopernicusElevationProviderKey) { image = TerrainTile::serializeFromAirMapJson(image); } QString format = getQGCMapEngine()->urlFactory()->getImageFormat(type, image); diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.cpp b/src/QtLocationPlugin/QGCMapUrlEngine.cpp index 3e076255f20..4ee56bdf87a 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.cpp +++ b/src/QtLocationPlugin/QGCMapUrlEngine.cpp @@ -32,6 +32,8 @@ QGC_LOGGING_CATEGORY(QGCMapUrlEngineLog, "QGCMapUrlEngineLog") #include #include +const char* UrlFactory::kCopernicusElevationProviderKey = "Copernicus Elevation"; + //----------------------------------------------------------------------------- UrlFactory::UrlFactory() : _timeout(5 * 1000) { @@ -75,7 +77,7 @@ UrlFactory::UrlFactory() : _timeout(5 * 1000) { _providersTable["VWorld Street Map"] = new VWorldStreetMapProvider(this); _providersTable["VWorld Satellite Map"] = new VWorldSatMapProvider(this); - _providersTable["Airmap Elevation"] = new AirmapElevationProvider(this); + _providersTable[kCopernicusElevationProviderKey] = new CopernicusElevationProvider(this); _providersTable["Japan-GSI Contour"] = new JapanStdMapProvider(this); _providersTable["Japan-GSI Seamless"] = new JapanSeamlessMapProvider(this); diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.h b/src/QtLocationPlugin/QGCMapUrlEngine.h index 6179fd4fa0d..b43301b0dc4 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.h +++ b/src/QtLocationPlugin/QGCMapUrlEngine.h @@ -29,6 +29,7 @@ class UrlFactory : public QObject { Q_OBJECT public: + static const char* kCopernicusElevationProviderKey; UrlFactory (); ~UrlFactory (); diff --git a/src/QtLocationPlugin/QMLControl/OfflineMap.qml b/src/QtLocationPlugin/QMLControl/OfflineMap.qml index b6a3d83ac32..5db10d441d9 100644 --- a/src/QtLocationPlugin/QMLControl/OfflineMap.qml +++ b/src/QtLocationPlugin/QMLControl/OfflineMap.qml @@ -522,7 +522,7 @@ Item { Row { spacing: ScreenTools.defaultFontPixelWidth anchors.horizontalCenter: parent.horizontalCenter - visible: !_defaultSet && mapType !== "Airmap Elevation" + visible: !_defaultSet && mapType !== QGroundControl.elevationProviderName QGCLabel { text: qsTr("Zoom Levels:"); width: infoView._labelWidth; } QGCLabel { text: offlineMapView._currentSelection ? (offlineMapView._currentSelection.minZoom + " - " + offlineMapView._currentSelection.maxZoom) : ""; horizontalAlignment: Text.AlignRight; width: infoView._valueWidth; } } diff --git a/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc b/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc index d1ed4d5eb58..ec4fe2dae67 100644 --- a/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc +++ b/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc @@ -28,6 +28,8 @@ QGC_LOGGING_CATEGORY(QGCMapEngineManagerLog, "QGCMapEngineManagerLog") static const char* kQmlOfflineMapKeyName = "QGCOfflineMap"; +static const auto kElevationMapType = UrlFactory::kCopernicusElevationProviderKey; + //----------------------------------------------------------------------------- QGCMapEngineManager::QGCMapEngineManager(QGCApplication* app, QGCToolbox* toolbox) : QGCTool(app, toolbox) @@ -84,7 +86,7 @@ QGCMapEngineManager::updateForCurrentView(double lon0, double lat0, double lon1, _imageSet += set; } if (_fetchElevation) { - QGCTileSet set = QGCMapEngine::getTileCount(1, lon0, lat0, lon1, lat1, "Airmap Elevation"); + QGCTileSet set = QGCMapEngine::getTileCount(1, lon0, lat0, lon1, lat1, kElevationMapType); _elevationSet += set; } @@ -159,9 +161,9 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType) } else { qWarning() << "QGCMapEngineManager::startDownload() No Tiles to save"; } - if (mapType != "Airmap Elevation" && _fetchElevation) { + if (mapType != kElevationMapType && _fetchElevation) { QGCCachedTileSet* set = new QGCCachedTileSet(name + " Elevation"); - set->setMapTypeStr("Airmap Elevation"); + set->setMapTypeStr(kElevationMapType); set->setTopleftLat(_topleftLat); set->setTopleftLon(_topleftLon); set->setBottomRightLat(_bottomRightLat); @@ -170,7 +172,7 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType) set->setMaxZoom(1); set->setTotalTileSize(_elevationSet.tileSize); set->setTotalTileCount(static_cast(_elevationSet.tileCount)); - set->setType("Airmap Elevation"); + set->setType(kElevationMapType); QGCCreateTileSetTask* task = new QGCCreateTileSetTask(set); //-- Create Tile Set (it will also create a list of tiles to download) connect(task, &QGCCreateTileSetTask::tileSetSaved, this, &QGCMapEngineManager::_tileSetSaved); diff --git a/src/Terrain/TerrainQuery.cc b/src/Terrain/TerrainQuery.cc index 10456c32481..4da3986dda5 100644 --- a/src/Terrain/TerrainQuery.cc +++ b/src/Terrain/TerrainQuery.cc @@ -33,6 +33,8 @@ QGC_LOGGING_CATEGORY(TerrainQueryVerboseLog, "TerrainQueryVerboseLog") Q_GLOBAL_STATIC(TerrainAtCoordinateBatchManager, _TerrainAtCoordinateBatchManager) Q_GLOBAL_STATIC(TerrainTileManager, _terrainTileManager) +static const auto kMapType = UrlFactory::kCopernicusElevationProviderKey; + TerrainAirMapQuery::TerrainAirMapQuery(QObject* parent) : TerrainQueryInterface(parent) { @@ -443,13 +445,17 @@ bool TerrainTileManager::getAltitudesForCoordinates(const QList& altitudes.push_back(elevation); } else { if (_state != State::Downloading) { - QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL("Airmap Elevation", getQGCMapEngine()->urlFactory()->long2tileX("Airmap Elevation",coordinate.longitude(), 1), getQGCMapEngine()->urlFactory()->lat2tileY("Airmap Elevation", coordinate.latitude(), 1), 1, &_networkManager); + QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL( + kMapType, getQGCMapEngine()->urlFactory()->long2tileX(kMapType, coordinate.longitude(), 1), + getQGCMapEngine()->urlFactory()->lat2tileY(kMapType, coordinate.latitude(), 1), + 1, + &_networkManager); qCDebug(TerrainQueryLog) << "TerrainTileManager::getAltitudesForCoordinates query from database" << request.url(); QGeoTileSpec spec; - spec.setX(getQGCMapEngine()->urlFactory()->long2tileX("Airmap Elevation", coordinate.longitude(), 1)); - spec.setY(getQGCMapEngine()->urlFactory()->lat2tileY("Airmap Elevation", coordinate.latitude(), 1)); + spec.setX(getQGCMapEngine()->urlFactory()->long2tileX(kMapType, coordinate.longitude(), 1)); + spec.setY(getQGCMapEngine()->urlFactory()->lat2tileY(kMapType, coordinate.latitude(), 1)); spec.setZoom(1); - spec.setMapId(getQGCMapEngine()->urlFactory()->getIdFromType("Airmap Elevation")); + spec.setMapId(getQGCMapEngine()->urlFactory()->getIdFromType(kMapType)); QGeoTiledMapReplyQGC* reply = new QGeoTiledMapReplyQGC(&_networkManager, request, spec); connect(reply, &QGeoTiledMapReplyQGC::terrainDone, this, &TerrainTileManager::_terrainDone); _state = State::Downloading; @@ -466,7 +472,7 @@ bool TerrainTileManager::getAltitudesForCoordinates(const QList& void TerrainTileManager::_tileFailed(void) { - QList noAltitudes; + QList noAltitudes; for (const QueuedRequestInfo_t& requestInfo: _requestQueue) { if (requestInfo.queryMode == QueryMode::QueryModeCoordinates) { @@ -490,7 +496,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N // remove from download queue QGeoTileSpec spec = reply->tileSpec(); - QString hash = QGCMapEngine::getTileHash("Airmap Elevation", spec.x(), spec.y(), spec.zoom()); + QString hash = QGCMapEngine::getTileHash(kMapType, spec.x(), spec.y(), spec.zoom()); // handle potential errors if (error != QNetworkReply::NoError) { @@ -557,9 +563,9 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N QString TerrainTileManager::_getTileHash(const QGeoCoordinate& coordinate) { QString ret = QGCMapEngine::getTileHash( - "Airmap Elevation", - getQGCMapEngine()->urlFactory()->long2tileX("Airmap Elevation", coordinate.longitude(), 1), - getQGCMapEngine()->urlFactory()->lat2tileY("Airmap Elevation", coordinate.latitude(), 1), + kMapType, + getQGCMapEngine()->urlFactory()->long2tileX(kMapType, coordinate.longitude(), 1), + getQGCMapEngine()->urlFactory()->lat2tileY(kMapType, coordinate.latitude(), 1), 1); qCDebug(TerrainQueryVerboseLog) << "Computing unique tile hash for " << coordinate << ret; diff --git a/src/TerrainTile.cc b/src/TerrainTile.cc index 654847fc58b..c651f2b1374 100644 --- a/src/TerrainTile.cc +++ b/src/TerrainTile.cc @@ -31,140 +31,120 @@ const char* TerrainTile::_jsonMinElevationKey = "min"; const char* TerrainTile::_jsonAvgElevationKey = "avg"; const char* TerrainTile::_jsonCarpetKey = "carpet"; -TerrainTile::TerrainTile() - : _minElevation(-1.0) - , _maxElevation(-1.0) - , _avgElevation(-1.0) - , _data(nullptr) - , _gridSizeLat(-1) - , _gridSizeLon(-1) - , _isValid(false) +TerrainTile::TerrainTile(const QByteArray& byteArray) { + // Copy tile info + _tileInfo = *reinterpret_cast(byteArray.constData()); -} - -TerrainTile::~TerrainTile() -{ - if (_data) { - for (int i = 0; i < _gridSizeLat; i++) { - delete[] _data[i]; - } - delete[] _data; - _data = nullptr; + // Check feasibility + if ((_tileInfo.neLon - _tileInfo.swLon) < 0.0 || (_tileInfo.neLat - _tileInfo.swLat) < 0.0) { + qCWarning(TerrainTileLog) << this << "Tile extent is infeasible"; + _isValid = false; + return; } -} -TerrainTile::TerrainTile(QByteArray byteArray) - : _minElevation(-1.0) - , _maxElevation(-1.0) - , _avgElevation(-1.0) - , _data(nullptr) - , _gridSizeLat(-1) - , _gridSizeLon(-1) - , _isValid(false) -{ + _cellSizeLat = (_tileInfo.neLat - _tileInfo.swLat) / _tileInfo.gridSizeLat; + _cellSizeLon = (_tileInfo.neLon - _tileInfo.swLon) / _tileInfo.gridSizeLon; + + qCDebug(TerrainTileLog) << this << "TileInfo: south west: " << _tileInfo.swLat << _tileInfo.swLon; + qCDebug(TerrainTileLog) << this << "TileInfo: north east: " << _tileInfo.neLat << _tileInfo.neLon; + qCDebug(TerrainTileLog) << this << "TileInfo: dimensions: " << _tileInfo.gridSizeLat << "by" << _tileInfo.gridSizeLat; + qCDebug(TerrainTileLog) << this << "TileInfo: min, max, avg: " << _tileInfo.minElevation << _tileInfo.maxElevation << _tileInfo.avgElevation; + qCDebug(TerrainTileLog) << this << "TileInfo: cell size: " << _cellSizeLat << _cellSizeLon; + int cTileHeaderBytes = static_cast(sizeof(TileInfo_t)); int cTileBytesAvailable = byteArray.size(); if (cTileBytesAvailable < cTileHeaderBytes) { - qWarning() << "Terrain tile binary data too small for TileInfo_s header"; + qCWarning(TerrainTileLog) << "Terrain tile binary data too small for TileInfo_s header"; return; } - const TileInfo_t* tileInfo = reinterpret_cast(byteArray.constData()); - _southWest.setLatitude(tileInfo->swLat); - _southWest.setLongitude(tileInfo->swLon); - _northEast.setLatitude(tileInfo->neLat); - _northEast.setLongitude(tileInfo->neLon); - _minElevation = tileInfo->minElevation; - _maxElevation = tileInfo->maxElevation; - _avgElevation = tileInfo->avgElevation; - _gridSizeLat = tileInfo->gridSizeLat; - _gridSizeLon = tileInfo->gridSizeLon; - - qCDebug(TerrainTileLog) << "Loading terrain tile: " << _southWest << " - " << _northEast; - qCDebug(TerrainTileLog) << "min:max:avg:sizeLat:sizeLon" << _minElevation << _maxElevation << _avgElevation << _gridSizeLat << _gridSizeLon; - - int cTileDataBytes = static_cast(sizeof(int16_t)) * _gridSizeLat * _gridSizeLon; + int cTileDataBytes = static_cast(sizeof(int16_t)) * _tileInfo.gridSizeLat * _tileInfo.gridSizeLon; if (cTileBytesAvailable < cTileHeaderBytes + cTileDataBytes) { - qWarning() << "Terrain tile binary data too small for tile data"; + qCWarning(TerrainTileLog) << "Terrain tile binary data too small for tile data"; return; } - _data = new int16_t*[_gridSizeLat]; - for (int k = 0; k < _gridSizeLat; k++) { - _data[k] = new int16_t[_gridSizeLon]; + _data = new int16_t*[_tileInfo.gridSizeLat]; + for (int k = 0; k < _tileInfo.gridSizeLat; k++) { + _data[k] = new int16_t[_tileInfo.gridSizeLon]; } int valueIndex = 0; const int16_t* pTileData = reinterpret_cast(&reinterpret_cast(byteArray.constData())[cTileHeaderBytes]); - for (int i = 0; i < _gridSizeLat; i++) { - for (int j = 0; j < _gridSizeLon; j++) { + for (int i = 0; i < _tileInfo.gridSizeLat; i++) { + for (int j = 0; j < _tileInfo.gridSizeLon; j++) { _data[i][j] = pTileData[valueIndex++]; } } _isValid = true; +} - return; +TerrainTile::~TerrainTile() +{ + if (!_data) { + return; + } + + for (unsigned i = 0; i < static_cast(_tileInfo.gridSizeLat); i++) { + delete[] _data[i]; + } + + delete[] _data; } double TerrainTile::elevation(const QGeoCoordinate& coordinate) const { - if (_isValid && _southWest.isValid() && _northEast.isValid()) { - qCDebug(TerrainTileLog) << "elevation: " << coordinate << " , in sw " << _southWest << " , ne " << _northEast; - - // The lat/lon values in _northEast and _southWest coordinates can have rounding errors such that the coordinate - // request may be slightly outside the tile box specified by these values. So we clamp the incoming values to the - // edges of the tile if needed. - - double clampedLon = qMax(coordinate.longitude(), _southWest.longitude()); - double clampedLat = qMax(coordinate.latitude(), _southWest.latitude()); - - // Calc the index of the southernmost and westernmost index data value - int lonIndex = qFloor((clampedLon - _southWest.longitude()) / tileValueSpacingDegrees); - int latIndex = qFloor((clampedLat - _southWest.latitude()) / tileValueSpacingDegrees); - - // Calc how far along in between the known values the requested lat/lon is fractionally - double lonIndexLongitude = _southWest.longitude() + (static_cast(lonIndex) * tileValueSpacingDegrees); - double lonFraction = (clampedLon - lonIndexLongitude) / tileValueSpacingDegrees; - double latIndexLatitude = _southWest.latitude() + (static_cast(latIndex) * tileValueSpacingDegrees); - double latFraction = (clampedLat - latIndexLatitude) / tileValueSpacingDegrees; - - // Calc the elevation as the average across the four known points - double known00 = _data[latIndex][lonIndex]; - double known01 = _data[latIndex][lonIndex+1]; - double known10 = _data[latIndex+1][lonIndex]; - double known11 = _data[latIndex+1][lonIndex+1]; - double lonValue1 = known00 + ((known01 - known00) * lonFraction); - double lonValue2 = known10 + ((known11 - known10) * lonFraction); - double latValue = lonValue1 + ((lonValue2 - lonValue1) * latFraction); - - return latValue; - } else { - qCWarning(TerrainTileLog) << "elevation: Internal error - invalid tile"; + if (!_isValid || !_data) { + qCWarning(TerrainTileLog) << this << "Request for elevation, but tile is invalid."; return qQNaN(); } -} -QGeoCoordinate TerrainTile::centerCoordinate(void) const -{ - return _southWest.atDistanceAndAzimuth(_southWest.distanceTo(_northEast) / 2.0, _southWest.azimuthTo(_northEast)); + const double latDeltaSw = coordinate.latitude() - _tileInfo.swLat; + const double lonDeltaSw = coordinate.longitude() - _tileInfo.swLon; + + const int16_t latIndex = qFloor(latDeltaSw / _cellSizeLat); + const int16_t lonIndex = qFloor(lonDeltaSw / _cellSizeLon); + + const bool latIndexInvalid = latIndex < 0 || latIndex > (_tileInfo.gridSizeLat - 1); + const bool lonIndexInvalid = lonIndex < 0 || lonIndex > (_tileInfo.gridSizeLon - 1); + + if (latIndexInvalid || lonIndexInvalid) { + qCWarning(TerrainTileLog) << this << "Internal error: coordinate" << coordinate << "outside tile bounds"; + return qQNaN(); + } + + const auto elevation = _data[latIndex][lonIndex]; + + // Print warning if elevation is outside min/max of tile meta data + if (elevation < _tileInfo.minElevation) { + qCWarning(TerrainTileLog) << this << "Warning: elevation read is below min elevation in tile:" << elevation << "<" << _tileInfo.minElevation; + } + else if (elevation > _tileInfo.maxElevation) { + qCWarning(TerrainTileLog) << this << "Warning: elevation read is above max elevation in tile:" << elevation << ">" << _tileInfo.maxElevation; + } + +#ifdef QT_DEBUG + qCDebug(TerrainTileLog) << this << "latIndex, lonIndex:" << latIndex << lonIndex << "elevation:" << elevation; +#endif + + return static_cast(elevation); } -QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) +QByteArray TerrainTile::serializeFromAirMapJson(const QByteArray& input) { QJsonParseError parseError; QJsonDocument document = QJsonDocument::fromJson(input, &parseError); if (parseError.error != QJsonParseError::NoError) { - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Terrain tile json doc parse error" << parseError.errorString(); + return QByteArray(); } if (!document.isObject()) { - qCDebug(TerrainTileLog) << "Terrain tile json doc is no object"; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Terrain tile json doc is no object"; + return QByteArray(); } QJsonObject rootObject = document.object(); @@ -174,15 +154,13 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) { _jsonDataKey, QJsonValue::Object, true }, }; if (!JsonHelper::validateKeys(rootObject, rootVersionKeyInfoList, errorString)) { - qCDebug(TerrainTileLog) << "Error in reading json: " << errorString; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Error in reading json: " << errorString; + return QByteArray(); } if (rootObject[_jsonStatusKey].toString() != "success") { - qCDebug(TerrainTileLog) << "Invalid terrain tile."; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Invalid terrain tile."; + return QByteArray(); } const QJsonObject& dataObject = rootObject[_jsonDataKey].toObject(); QList dataVersionKeyInfoList = { @@ -191,9 +169,8 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) { _jsonCarpetKey, QJsonValue::Array, true }, }; if (!JsonHelper::validateKeys(dataObject, dataVersionKeyInfoList, errorString)) { - qCDebug(TerrainTileLog) << "Error in reading json: " << errorString; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Error in reading json: " << errorString; + return QByteArray(); } // Bounds @@ -203,18 +180,24 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) { _jsonNorthEastKey, QJsonValue::Array, true }, }; if (!JsonHelper::validateKeys(boundsObject, boundsVersionKeyInfoList, errorString)) { - qCDebug(TerrainTileLog) << "Error in reading json: " << errorString; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Error in reading json: " << errorString; + return QByteArray(); } const QJsonArray& swArray = boundsObject[_jsonSouthWestKey].toArray(); const QJsonArray& neArray = boundsObject[_jsonNorthEastKey].toArray(); if (swArray.count() < 2 || neArray.count() < 2 ) { - qCDebug(TerrainTileLog) << "Incomplete bounding location"; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Incomplete bounding location"; + return QByteArray(); } + const double swLat = swArray[0].toDouble(); + const double swLon = swArray[1].toDouble(); + const double neLat = neArray[0].toDouble(); + const double neLon = neArray[1].toDouble(); + + qCDebug(TerrainTileLog) << "Serialize: swArray: south west: " << (40.42 - swLat) << (-3.23 - swLon); + qCDebug(TerrainTileLog) << "Serialize: neArray: north east: " << neLat << neLon; + // Stats const QJsonObject& statsObject = dataObject[_jsonStatsKey].toObject(); QList statsVersionKeyInfoList = { @@ -223,18 +206,14 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) { _jsonAvgElevationKey, QJsonValue::Double, true }, }; if (!JsonHelper::validateKeys(statsObject, statsVersionKeyInfoList, errorString)) { - qCDebug(TerrainTileLog) << "Error in reading json: " << errorString; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Error in reading json: " << errorString; + return QByteArray(); } - // Carpet const QJsonArray& carpetArray = dataObject[_jsonCarpetKey].toArray(); - int gridSizeLat = carpetArray.count(); - int gridSizeLon = carpetArray[0].toArray().count(); - - TileInfo_t tileInfo; + // Tile meta data + TerrainTile::TileInfo_t tileInfo; tileInfo.swLat = swArray[0].toDouble(); tileInfo.swLon = swArray[1].toDouble(); tileInfo.neLat = neArray[0].toDouble(); @@ -242,41 +221,34 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) tileInfo.minElevation = static_cast(statsObject[_jsonMinElevationKey].toInt()); tileInfo.maxElevation = static_cast(statsObject[_jsonMaxElevationKey].toInt()); tileInfo.avgElevation = statsObject[_jsonAvgElevationKey].toDouble(); - tileInfo.gridSizeLat = static_cast(gridSizeLat); - tileInfo.gridSizeLon = static_cast(gridSizeLon); - - // We require 1-arc second value spacing - double neCornerLatExpected = tileInfo.swLat + ((tileInfo.gridSizeLat - 1) * tileValueSpacingDegrees); - double neCornerLonExpected = tileInfo.swLon + ((tileInfo.gridSizeLon - 1) * tileValueSpacingDegrees); - if (!QGC::fuzzyCompare(tileInfo.neLat, neCornerLatExpected) || !QGC::fuzzyCompare(tileInfo.neLon, neCornerLonExpected)) { - qCWarning(TerrainTileLog) << QStringLiteral("serialize: Internal error - distance between values incorrect neExpected(%1, %2) neActual(%3, %4) sw(%5, %6) gridSize(%7, %8)") - .arg(neCornerLatExpected).arg(neCornerLonExpected).arg(tileInfo.neLat).arg(tileInfo.neLon).arg(tileInfo.swLat).arg(tileInfo.swLon).arg(tileInfo.gridSizeLat).arg(tileInfo.gridSizeLon); - QByteArray emptyArray; - return emptyArray; - } + tileInfo.gridSizeLat = static_cast(carpetArray.count()); + tileInfo.gridSizeLon = static_cast(carpetArray[0].toArray().count()); - int cTileHeaderBytes = static_cast(sizeof(TileInfo_t)); - int cTileDataBytes = static_cast(sizeof(int16_t)) * gridSizeLat * gridSizeLon; + qCDebug(TerrainTileLog) << "Serialize: TileInfo: south west: " << tileInfo.swLat << tileInfo.swLon; + qCDebug(TerrainTileLog) << "Serialize: TileInfo: north east: " << tileInfo.neLat << tileInfo.neLon; + + const auto cTileNumHeaderBytes = static_cast(sizeof(TileInfo_t)); + const auto cTileNumDataBytes = static_cast(sizeof(int16_t)) * tileInfo.gridSizeLat * tileInfo.gridSizeLon; - QByteArray byteArray(cTileHeaderBytes + cTileDataBytes, 0); + QByteArray res; + res.resize(cTileNumHeaderBytes + cTileNumDataBytes); - TileInfo_t* pTileInfo = reinterpret_cast(byteArray.data()); - int16_t* pTileData = reinterpret_cast(&reinterpret_cast(byteArray.data())[cTileHeaderBytes]); + TileInfo_t* pTileInfo = reinterpret_cast(res.data()); + int16_t* pTileData = reinterpret_cast(&reinterpret_cast(res.data())[cTileNumHeaderBytes]); *pTileInfo = tileInfo; int valueIndex = 0; - for (int i = 0; i < gridSizeLat; i++) { + for (unsigned i = 0; i < static_cast(tileInfo.gridSizeLat); i++) { const QJsonArray& row = carpetArray[i].toArray(); - if (row.count() < gridSizeLon) { - qCDebug(TerrainTileLog) << "Expected row array of " << gridSizeLon << ", instead got " << row.count(); - QByteArray emptyArray; - return emptyArray; + if (row.count() < tileInfo.gridSizeLon) { + qCDebug(TerrainTileLog) << "Expected row array of " << tileInfo.gridSizeLon << ", instead got " << row.count(); + return QByteArray(); } - for (int j = 0; j < gridSizeLon; j++) { + for (unsigned j = 0; j < static_cast(tileInfo.gridSizeLon); j++) { pTileData[valueIndex++] = static_cast(row[j].toDouble()); } } - return byteArray; + return res; } diff --git a/src/TerrainTile.h b/src/TerrainTile.h index bd1417df621..01345939089 100644 --- a/src/TerrainTile.h +++ b/src/TerrainTile.h @@ -16,7 +16,7 @@ Q_DECLARE_LOGGING_CATEGORY(TerrainTileLog) class TerrainTile { public: - TerrainTile(); + TerrainTile() = default; ~TerrainTile(); /** @@ -24,7 +24,7 @@ class TerrainTile * * @param document */ - TerrainTile(QByteArray byteArray); + TerrainTile(const QByteArray& byteArray); /** * Check whether valid data is loaded @@ -46,30 +46,29 @@ class TerrainTile * * @return minimum elevation */ - double minElevation(void) const { return _minElevation; } + double minElevation(void) const { return _isValid ? static_cast(_tileInfo.minElevation) : qQNaN(); } /** * Accessor for the maximum elevation of the tile * * @return maximum elevation */ - double maxElevation(void) const { return _maxElevation; } + double maxElevation(void) const { return _isValid ? static_cast(_tileInfo.maxElevation) : qQNaN(); } /** * Accessor for the average elevation of the tile * * @return average elevation */ - double avgElevation(void) const { return _avgElevation; } + double avgElevation(void) const { return _isValid ? _tileInfo.avgElevation : qQNaN(); } /** * Accessor for the center coordinate * * @return center coordinate */ - QGeoCoordinate centerCoordinate(void) const; - static QByteArray serializeFromAirMapJson(QByteArray input); + static QByteArray serializeFromAirMapJson(const QByteArray& input); static constexpr double tileSizeDegrees = 0.01; ///< Each terrain tile represents a square area .01 degrees in lat/lon static constexpr double tileValueSpacingDegrees = 1.0 / 3600; ///< 1 Arc-Second spacing of elevation values @@ -77,7 +76,7 @@ class TerrainTile private: typedef struct { - double swLat,swLon, neLat, neLon; + double swLat, swLon, neLat, neLon; int16_t minElevation; int16_t maxElevation; double avgElevation; @@ -85,16 +84,10 @@ class TerrainTile int16_t gridSizeLon; } TileInfo_t; - QGeoCoordinate _southWest; /// South west corner of the tile - QGeoCoordinate _northEast; /// North east corner of the tile - - int16_t _minElevation; /// Minimum elevation in tile - int16_t _maxElevation; /// Maximum elevation in tile - double _avgElevation; /// Average elevation of the tile - + TileInfo_t _tileInfo; int16_t** _data; /// 2D elevation data array - int16_t _gridSizeLat; /// data grid size in latitude direction - int16_t _gridSizeLon; /// data grid size in longitude direction + double _cellSizeLat; /// data grid size in latitude direction + double _cellSizeLon; /// data grid size in longitude direction bool _isValid; /// data loaded is valid // Json keys From f658b748367a24bfb70bd3d112b19b1d601c0e52 Mon Sep 17 00:00:00 2001 From: leonardosimovic Date: Wed, 26 Jul 2023 09:48:50 +0200 Subject: [PATCH 042/118] feat: give credit to elevation provider --- src/PlanView/PlanView.qml | 13 +++++++++++++ src/PlanView/TerrainStatus.qml | 1 - src/QmlControls/QGroundControlQmlGlobal.h | 3 +++ src/QtLocationPlugin/QGCMapUrlEngine.cpp | 9 +++++---- src/QtLocationPlugin/QGCMapUrlEngine.h | 1 + 5 files changed, 22 insertions(+), 5 deletions(-) diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml index a96928cb675..98ad6ff497a 100644 --- a/src/PlanView/PlanView.qml +++ b/src/PlanView/PlanView.qml @@ -730,6 +730,19 @@ Item { } } + QGCLabel { + // Elevation provider notice on top of terrain plot + readonly property string _licenseString: QGroundControl.elevationProviderNotice + + id: licenseLabel + visible: terrainStatus.visible && _licenseString !== "" + anchors.bottom: terrainStatus.top + anchors.horizontalCenter: terrainStatus.horizontalCenter + anchors.bottomMargin: ScreenTools.defaultFontPixelWidth * 0.5 + font.pointSize: ScreenTools.smallFontPointSize + text: qsTr("Powered by %1").arg(_licenseString) + } + TerrainStatus { id: terrainStatus anchors.margins: _toolsMargin diff --git a/src/PlanView/TerrainStatus.qml b/src/PlanView/TerrainStatus.qml index 51f11099816..fe3418de085 100644 --- a/src/PlanView/TerrainStatus.qml +++ b/src/PlanView/TerrainStatus.qml @@ -50,7 +50,6 @@ Rectangle { QGCFlickable { id: terrainProfileFlickable - //anchors.margins: _margins anchors.top: parent.top anchors.bottom: parent.bottom anchors.leftMargin: titleLabel.contentHeight diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h index ff17e4452d0..1a54275ad93 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.h +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -109,6 +109,8 @@ class QGroundControlQmlGlobal : public QGCTool //------------------------------------------------------------------------- // Elevation Provider Q_PROPERTY(QString elevationProviderName READ elevationProviderName CONSTANT) + Q_PROPERTY(QString elevationProviderNotice READ elevationProviderNotice CONSTANT) + #if defined(QGC_ENABLE_PAIRING) Q_PROPERTY(PairingManager* pairingManager READ pairingManager CONSTANT) @@ -208,6 +210,7 @@ class QGroundControlQmlGlobal : public QGCTool #endif QString elevationProviderName () { return UrlFactory::kCopernicusElevationProviderKey; } + QString elevationProviderNotice () { return UrlFactory::kCopernicusElevationProviderNotice; } bool singleFirmwareSupport (); bool singleVehicleSupport (); diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.cpp b/src/QtLocationPlugin/QGCMapUrlEngine.cpp index 4ee56bdf87a..7f4cbfd02b5 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.cpp +++ b/src/QtLocationPlugin/QGCMapUrlEngine.cpp @@ -33,6 +33,7 @@ QGC_LOGGING_CATEGORY(QGCMapUrlEngineLog, "QGCMapUrlEngineLog") #include const char* UrlFactory::kCopernicusElevationProviderKey = "Copernicus Elevation"; +const char* UrlFactory::kCopernicusElevationProviderNotice = "© Airbus Defence and Space GmbH"; //----------------------------------------------------------------------------- UrlFactory::UrlFactory() : _timeout(5 * 1000) { @@ -73,7 +74,7 @@ UrlFactory::UrlFactory() : _timeout(5 * 1000) { //_providersTable["MapQuest Map"] = new MapQuestMapMapProvider(this); //_providersTable["MapQuest Sat"] = new MapQuestSatMapProvider(this); - + _providersTable["VWorld Street Map"] = new VWorldStreetMapProvider(this); _providersTable["VWorld Satellite Map"] = new VWorldSatMapProvider(this); @@ -84,9 +85,9 @@ UrlFactory::UrlFactory() : _timeout(5 * 1000) { _providersTable["Japan-GSI Anaglyph"] = new JapanAnaglyphMapProvider(this); _providersTable["Japan-GSI Slope"] = new JapanSlopeMapProvider(this); _providersTable["Japan-GSI Relief"] = new JapanReliefMapProvider(this); - + _providersTable["LINZ Basemap"] = new LINZBasemapMapProvider(this); - + _providersTable["CustomURL Custom"] = new CustomURLMapProvider(this); } @@ -142,7 +143,7 @@ QNetworkRequest UrlFactory::getTileURL(const QString& type, int x, int y, int zo quint32 UrlFactory::averageSizeForType(const QString& type) { if (_providersTable.find(type) != _providersTable.end()) { return _providersTable[type]->getAverageSize(); - } + } qCDebug(QGCMapUrlEngineLog) << "UrlFactory::averageSizeForType " << type << " Not registered"; diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.h b/src/QtLocationPlugin/QGCMapUrlEngine.h index b43301b0dc4..8d3535c84ac 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.h +++ b/src/QtLocationPlugin/QGCMapUrlEngine.h @@ -30,6 +30,7 @@ class UrlFactory : public QObject { Q_OBJECT public: static const char* kCopernicusElevationProviderKey; + static const char* kCopernicusElevationProviderNotice; UrlFactory (); ~UrlFactory (); From 5ba152bd4c76f81f14c64d5f66509c66347eb55d Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Mon, 28 Aug 2023 16:33:36 +0000 Subject: [PATCH 043/118] Update PX4 Firmware metadata Mon Aug 28 16:33:36 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 8 -------- 1 file changed, 8 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 89bfc15b2a5..55280a109b0 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -10885,14 +10885,6 @@ 3 0.01 - - Tilt when disarmed and in the first second after arming - This specific tilt during spin-up is necessary for some systems whose motors otherwise don't spin-up freely. - 0.0 - 1.0 - 2 - 0.01 - Normalized tilt in transition to FW 0.0 From d2712f891a9122790a1d8ecc71a1199cd703f947 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 28 Aug 2023 12:43:53 -0700 Subject: [PATCH 044/118] Joysticks buttons only support, allow joystick selection override --- src/Joystick/Joystick.cc | 6 ++++-- src/Joystick/JoystickManager.cc | 11 ++++++----- src/Joystick/JoystickManager.h | 2 +- src/Vehicle/Vehicle.cc | 2 +- src/VehicleSetup/JoystickConfig.qml | 17 +++++++++++++++-- src/VehicleSetup/JoystickConfigGeneral.qml | 16 ++++++++++++---- src/VehicleSetup/SetupView.qml | 2 +- src/api/QGCOptions.h | 3 +++ 8 files changed, 43 insertions(+), 16 deletions(-) diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index 7c03360a3d4..ddc3ed3cfb5 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -501,7 +501,9 @@ void Joystick::run() while (!_exitThread) { _update(); _handleButtons(); - _handleAxis(); + if (axisCount() != 0) { + _handleAxis(); + } QGC::SLEEP::msleep(qMin(static_cast(1000.0f / _maxAxisFrequencyHz), static_cast(1000.0f / _maxButtonFrequencyHz)) / 2); } _close(); @@ -719,7 +721,7 @@ void Joystick::startPolling(Vehicle* vehicle) // Always set up the new vehicle _activeVehicle = vehicle; // If joystick is not calibrated, disable it - if ( !_calibrated ) { + if ( axisCount() != 0 && !_calibrated ) { vehicle->setJoystickEnabled(false); } // Update qml in case of joystick transition diff --git a/src/Joystick/JoystickManager.cc b/src/Joystick/JoystickManager.cc index 0cba1911eac..bd03f154775 100644 --- a/src/Joystick/JoystickManager.cc +++ b/src/Joystick/JoystickManager.cc @@ -175,14 +175,15 @@ QString JoystickManager::activeJoystickName(void) return _activeJoystick ? _activeJoystick->name() : QString(); } -void JoystickManager::setActiveJoystickName(const QString& name) +bool JoystickManager::setActiveJoystickName(const QString& name) { - if (!_name2JoystickMap.contains(name)) { + if (_name2JoystickMap.contains(name)) { + setActiveJoystick(_name2JoystickMap[name]); + return true; + } else { qCWarning(JoystickManagerLog) << "Set active not in map" << name; - return; + return false; } - - setActiveJoystick(_name2JoystickMap[name]); } /* diff --git a/src/Joystick/JoystickManager.h b/src/Joystick/JoystickManager.h index f4f939a8b67..6614501dbc8 100644 --- a/src/Joystick/JoystickManager.h +++ b/src/Joystick/JoystickManager.h @@ -47,7 +47,7 @@ class JoystickManager : public QGCTool void setActiveJoystick(Joystick* joystick); QString activeJoystickName(void); - void setActiveJoystickName(const QString& name); + bool setActiveJoystickName(const QString& name); void restartJoystickCheckTimer(void); diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 91280aac31e..ea4d8589d0f 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -2156,7 +2156,7 @@ void Vehicle::_captureJoystick() Joystick* joystick = _joystickManager->activeJoystick(); if(joystick){ - qCDebug(JoystickLog) << "Vehicle " << this->id() << " Capture Joystick"; + qCDebug(JoystickLog) << "Vehicle " << this->id() << " Capture Joystick" << joystick->name(); joystick->startPolling(this); } } diff --git a/src/VehicleSetup/JoystickConfig.qml b/src/VehicleSetup/JoystickConfig.qml index 3ba6e90b67e..c7d4f1bc2e2 100644 --- a/src/VehicleSetup/JoystickConfig.qml +++ b/src/VehicleSetup/JoystickConfig.qml @@ -48,7 +48,9 @@ SetupPage { height: bar.height + joyLoader.height readonly property real labelToMonitorMargin: ScreenTools.defaultFontPixelWidth * 3 - property var _activeJoystick: joystickManager.activeJoystick + + property var _activeJoystick: joystickManager.activeJoystick + property bool _allowJoystickSelection: QGroundControl.corePlugin.options.allowJoystickSelection function setupPageCompleted() { controller.start() @@ -62,20 +64,31 @@ SetupPage { id: bar width: parent.width Component.onCompleted: { - currentIndex = _activeJoystick && _activeJoystick.calibrated ? 0 : 2 + if (_activeJoystick) { + if (_activeJoystick.axisCount == 0) { + currentIndex = _allowJoystickSelection ? 0 : 1 + } else { + currentIndex = _activeJoystick.calibrated ? 0 : 2 + } + } else { + currentIndex = 0 + } } anchors.top: parent.top QGCTabButton { text: qsTr("General") + visible: _allowJoystickSelection } QGCTabButton { text: qsTr("Button Assigment") } QGCTabButton { text: qsTr("Calibration") + visible: _activeJoystick.axisCount != 0 } QGCTabButton { text: qsTr("Advanced") + visible: _activeJoystick.axisCount != 0 } } diff --git a/src/VehicleSetup/JoystickConfigGeneral.qml b/src/VehicleSetup/JoystickConfigGeneral.qml index 4e846d05eed..8a479a110a8 100644 --- a/src/VehicleSetup/JoystickConfigGeneral.qml +++ b/src/VehicleSetup/JoystickConfigGeneral.qml @@ -21,9 +21,14 @@ import QGroundControl.FactSystem 1.0 import QGroundControl.FactControls 1.0 Item { - width: mainCol.width + (ScreenTools.defaultFontPixelWidth * 2) - height: mainCol.height + (ScreenTools.defaultFontPixelHeight * 2) + width: mainCol.width + (ScreenTools.defaultFontPixelWidth * 2) + height: mainCol.height + (ScreenTools.defaultFontPixelHeight * 2) + readonly property real axisMonitorWidth: ScreenTools.defaultFontPixelWidth * 32 + + property bool _buttonsOnly: _activeJoystick.axisCount == 0 + property bool _requiresCalibration: !_activeJoystick.calibrated && !_buttonsOnly + Column { id: mainCol anchors.centerIn: parent @@ -35,13 +40,13 @@ Item { //--------------------------------------------------------------------- //-- Enable Joystick QGCLabel { - text: _activeJoystick ? _activeJoystick.calibrated ? qsTr("Enable joystick input") : qsTr("Enable not allowed (Calibrate First)") : "" + text: _requiresCalibration ? qsTr("Enable not allowed (Calibrate First)") : qsTr("Enable joystick input") Layout.alignment: Qt.AlignVCenter Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 36 } QGCCheckBox { id: enabledSwitch - enabled: _activeJoystick ? _activeJoystick.calibrated : false + enabled: !_requiresCalibration onClicked: { globals.activeVehicle.joystickEnabled = checked globals.activeVehicle.saveJoystickSettings() @@ -99,9 +104,11 @@ Item { QGCLabel { text: qsTr("RC Mode:") Layout.alignment: Qt.AlignVCenter + visible: !_buttonsOnly } Row { spacing: ScreenTools.defaultFontPixelWidth + visible: !_buttonsOnly QGCRadioButton { text: "1" checked: controller.transmitterMode === 1 @@ -144,6 +151,7 @@ Item { radius: ScreenTools.defaultFontPixelWidth * 0.5 width: axisGrid.width + (ScreenTools.defaultFontPixelWidth * 2) height: axisGrid.height + (ScreenTools.defaultFontPixelHeight * 2) + visible: !_buttonsOnly GridLayout { id: axisGrid columns: 2 diff --git a/src/VehicleSetup/SetupView.qml b/src/VehicleSetup/SetupView.qml index 70946d1edc2..715f9b6caf0 100644 --- a/src/VehicleSetup/SetupView.qml +++ b/src/VehicleSetup/SetupView.qml @@ -260,7 +260,7 @@ Rectangle { id: joystickButton imageResource: "/qmlimages/Joystick.png" setupIndicator: true - setupComplete: joystickManager.activeJoystick ? joystickManager.activeJoystick.calibrated : false + setupComplete: joystickManager.activeJoystick ? joystickManager.activeJoystick.calibrated || joystickManager.activeJoystick.axisCount == 0 : false exclusiveGroup: setupButtonGroup visible: _fullParameterVehicleAvailable && joystickManager.joysticks.length !== 0 text: qsTr("Joystick") diff --git a/src/api/QGCOptions.h b/src/api/QGCOptions.h index 43f01167d0c..7b5926d5574 100644 --- a/src/api/QGCOptions.h +++ b/src/api/QGCOptions.h @@ -80,6 +80,7 @@ class QGCOptions : public QObject Q_PROPERTY(bool showMavlinkLogOptions READ showMavlinkLogOptions CONSTANT) Q_PROPERTY(bool enableSaveMainWindowPosition READ enableSaveMainWindowPosition CONSTANT) Q_PROPERTY(QStringList surveyBuiltInPresetNames READ surveyBuiltInPresetNames CONSTANT) + Q_PROPERTY(bool allowJoystickSelection READ allowJoystickSelection NOTIFY allowJoystickSelectionChanged) Q_PROPERTY(QGCFlyViewOptions* flyView READ flyViewOptions CONSTANT) @@ -125,6 +126,7 @@ class QGCOptions : public QObject virtual bool disableVehicleConnection () const { return false; } ///< true: vehicle connection is disabled virtual bool checkFirmwareVersion () const { return true; } virtual bool showMavlinkLogOptions () const { return true; } + virtual bool allowJoystickSelection () const { return true; } ///< false: custom build has automatically enabled a specific joystick /// Desktop builds save the main application size and position on close (and restore it on open) virtual bool enableSaveMainWindowPosition () const { return true; } virtual QStringList surveyBuiltInPresetNames () const { return QStringList(); } // Built in presets cannot be deleted @@ -155,6 +157,7 @@ class QGCOptions : public QObject void showFirmwareUpgradeChanged (bool show); void missionWaypointsOnlyChanged (bool missionWaypointsOnly); void multiVehicleEnabledChanged (bool multiVehicleEnabled); + void allowJoystickSelectionChanged (bool allow); void showOfflineMapExportChanged (); void showOfflineMapImportChanged (); void showMissionAbsoluteAltitudeChanged (); From 26f9b4805ad38fb522a9c155fd76c742f4aa7ea2 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Thu, 24 Aug 2023 12:04:52 -0700 Subject: [PATCH 045/118] Add numericValuesOnly support --- src/FactSystem/FactControls/FactTextField.qml | 13 +++++-------- src/QmlControls/QGCTextField.qml | 4 ++++ 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/src/FactSystem/FactControls/FactTextField.qml b/src/FactSystem/FactControls/FactTextField.qml index 6bbd381c8f1..d22500bbe9a 100644 --- a/src/FactSystem/FactControls/FactTextField.qml +++ b/src/FactSystem/FactControls/FactTextField.qml @@ -11,10 +11,11 @@ import QGroundControl.ScreenTools 1.0 QGCTextField { id: _textField - text: fact ? fact.valueString : "" - unitsLabel: fact ? fact.units : "" - showUnits: true - showHelp: true + text: fact ? fact.valueString : "" + unitsLabel: fact ? fact.units : "" + showUnits: true + showHelp: true + numericValuesOnly: fact && !fact.typeIsString signal updated() @@ -22,10 +23,6 @@ QGCTextField { property string _validateString - inputMethodHints: ((fact && fact.typeIsString) || ScreenTools.isiOS) ? - Qt.ImhNone : // iOS numeric keyboard has no done button, we can't use it - Qt.ImhFormattedNumbersOnly // Forces use of virtual numeric keyboard - onEditingFinished: { var errorString = fact.validate(text, false /* convertOnly */) if (errorString === "") { diff --git a/src/QmlControls/QGCTextField.qml b/src/QmlControls/QGCTextField.qml index 317ffd8ffa2..560cf8fd014 100644 --- a/src/QmlControls/QGCTextField.qml +++ b/src/QmlControls/QGCTextField.qml @@ -12,11 +12,15 @@ TextField { implicitHeight: ScreenTools.implicitTextFieldHeight activeFocusOnPress: true antialiasing: true + inputMethodHints: numericValuesOnly && !ScreenTools.isiOS ? + Qt.ImhNone : // iOS numeric keyboard has no done button, we can't use it. + Qt.ImhFormattedNumbersOnly // Forces use of virtual numeric keyboard instead of full keyboard property bool showUnits: false property bool showHelp: false property string unitsLabel: "" property string extraUnitsLabel: "" + property bool numericValuesOnly: false // true: Used as hint for mobile devices to show numeric only keyboard signal helpClicked From ac5096ef9cf4d0a5726f597b6a7c3555ee279091 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Thu, 24 Aug 2023 12:05:08 -0700 Subject: [PATCH 046/118] Set numericValuesOnly on calculator entry fields --- src/AutoPilotPlugins/PX4/PowerComponent.qml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/AutoPilotPlugins/PX4/PowerComponent.qml b/src/AutoPilotPlugins/PX4/PowerComponent.qml index 9768b2269d1..659600b8f09 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponent.qml +++ b/src/AutoPilotPlugins/PX4/PowerComponent.qml @@ -439,7 +439,7 @@ SetupPage { columns: 2 QGCLabel { text: qsTr("Measured voltage:") } - QGCTextField { id: measuredVoltage } + QGCTextField { id: measuredVoltage; numericValuesOnly: true } QGCLabel { text: qsTr("Vehicle voltage:") } QGCLabel { text: _batteryFactGroup.voltage.valueString } @@ -497,7 +497,7 @@ SetupPage { columns: 2 QGCLabel { text: qsTr("Measured current:") } - QGCTextField { id: measuredCurrent } + QGCTextField { id: measuredCurrent; numericValuesOnly: true } QGCLabel { text: qsTr("Vehicle current:") } QGCLabel { text: _batteryFactGroup.current.valueString } From 6f5cdca6afac77cdd219cd86410648a09bc4ae44 Mon Sep 17 00:00:00 2001 From: James Mare Date: Tue, 4 Jul 2023 17:06:35 +1000 Subject: [PATCH 047/118] Implement APM circle geofence from params Both PX4 and APM supports circular geofences around the home point. QGC with PX4 displays this by checking GF_MAX_HOR_DIST. This commit adds equivalent functionality for APM. Params used on APM are FENCE_ENABLE,FENCE_TYPE,FENCE_RADIUS. Tested with ArduCopter 4.3, ArduPlane master, and PX4 1.13. --- src/MissionManager/GeoFenceController.cc | 87 ++++++++++++++++++++++-- src/MissionManager/GeoFenceController.h | 13 +++- 2 files changed, 91 insertions(+), 9 deletions(-) diff --git a/src/MissionManager/GeoFenceController.cc b/src/MissionManager/GeoFenceController.cc index 4e3042d192e..7092d1f1053 100644 --- a/src/MissionManager/GeoFenceController.cc +++ b/src/MissionManager/GeoFenceController.cc @@ -39,6 +39,9 @@ const char* GeoFenceController::_jsonCirclesKey = "circles"; const char* GeoFenceController::_breachReturnAltitudeFactName = "Altitude"; const char* GeoFenceController::_px4ParamCircularFence = "GF_MAX_HOR_DIST"; +const char* GeoFenceController::_apmParamCircularFenceRadius = "FENCE_RADIUS"; +const char* GeoFenceController::_apmParamCircularFenceEnabled = "FENCE_ENABLE"; +const char* GeoFenceController::_apmParamCircularFenceType = "FENCE_TYPE"; GeoFenceController::GeoFenceController(PlanMasterController* masterController, QObject* parent) : PlanElementController (masterController, parent) @@ -495,30 +498,102 @@ bool GeoFenceController::supported(void) const return (_managerVehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE) && (_managerVehicle->maxProtoVersion() >= 200); } -// Hack for PX4 +/* Returns the radius of the "paramCircularFence" + * which is called the "Geofence Failsafe" in PX4 and the "Circular Geofence" on Ardupilot + * this code should ideally live in the firmware plugin since it is specific to apm and px4 firmwares */ double GeoFenceController::paramCircularFence(void) { - if (_managerVehicle->isOfflineEditingVehicle() || !_managerVehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _px4ParamCircularFence)) { + if(_managerVehicle->isOfflineEditingVehicle()){ return 0; } - return _managerVehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _px4ParamCircularFence)->rawValue().toDouble(); + if(_managerVehicle->px4Firmware()){ + if(!_managerVehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _px4ParamCircularFence)){ + return 0; + } + + return _managerVehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _px4ParamCircularFence)->rawValue().toDouble(); + } + + if(_managerVehicle->apmFirmware()) + { + if (!_managerVehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _apmParamCircularFenceRadius) || + !_managerVehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _apmParamCircularFenceEnabled) || + !_managerVehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _apmParamCircularFenceType)){ + return 0; + } + + bool apm_fence_enabled = _managerVehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _apmParamCircularFenceEnabled)->rawValue().toBool(); + bool apm_fence_type_circle = (1 << 1) & _managerVehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _apmParamCircularFenceType)->rawValue().toUInt(); + + if(!apm_fence_enabled || !apm_fence_type_circle) + return 0; + + return _managerVehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _apmParamCircularFenceRadius)->rawValue().toDouble(); + } + + return 0; } void GeoFenceController::_parametersReady(void) { + /* When parameters are ready we setup notifications of param changes + * so that if a param changes we can emit paramCircularFenceChanged + * and trigger an update to the UI */ + + // First disconnect from any existing facts if (_px4ParamCircularFenceFact) { _px4ParamCircularFenceFact->disconnect(this); _px4ParamCircularFenceFact = nullptr; } + if (_apmParamCircularFenceRadiusFact) { + _apmParamCircularFenceRadiusFact->disconnect(this); + _apmParamCircularFenceRadiusFact = nullptr; + } + if (_apmParamCircularFenceEnabledFact) { + _apmParamCircularFenceEnabledFact->disconnect(this); + _apmParamCircularFenceEnabledFact = nullptr; + } + if (_apmParamCircularFenceTypeFact) { + _apmParamCircularFenceTypeFact->disconnect(this); + _apmParamCircularFenceTypeFact = nullptr; + } - if (_managerVehicle->isOfflineEditingVehicle() || !_managerVehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _px4ParamCircularFence)) { + // then connect to needed paremters + // While checking they exist to avoid errors + ParameterManager* _paramManager = _managerVehicle->parameterManager(); + + if(_managerVehicle->isOfflineEditingVehicle()){ emit paramCircularFenceChanged(); return; } - _px4ParamCircularFenceFact = _managerVehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _px4ParamCircularFence); - connect(_px4ParamCircularFenceFact, &Fact::rawValueChanged, this, &GeoFenceController::paramCircularFenceChanged); + if(_managerVehicle->px4Firmware()){ + if(!_paramManager->parameterExists(FactSystem::defaultComponentId, _px4ParamCircularFence)){ + emit paramCircularFenceChanged(); + return; + } + + _px4ParamCircularFenceFact = _paramManager->getParameter(FactSystem::defaultComponentId, _px4ParamCircularFence); + connect(_px4ParamCircularFenceFact, &Fact::rawValueChanged, this, &GeoFenceController::paramCircularFenceChanged); + } + else if(_managerVehicle->apmFirmware()) + { + if (!_paramManager->parameterExists(FactSystem::defaultComponentId, _apmParamCircularFenceRadius) || + !_paramManager->parameterExists(FactSystem::defaultComponentId, _apmParamCircularFenceEnabled) || + !_paramManager->parameterExists(FactSystem::defaultComponentId, _apmParamCircularFenceType)){ + emit paramCircularFenceChanged(); + return; + } + + _apmParamCircularFenceRadiusFact = _paramManager->getParameter(FactSystem::defaultComponentId, _apmParamCircularFenceRadius); + _apmParamCircularFenceEnabledFact = _paramManager->getParameter(FactSystem::defaultComponentId, _apmParamCircularFenceEnabled); + _apmParamCircularFenceTypeFact = _paramManager->getParameter(FactSystem::defaultComponentId, _apmParamCircularFenceType); + connect(_apmParamCircularFenceRadiusFact, &Fact::rawValueChanged, this, &GeoFenceController::paramCircularFenceChanged); + connect(_apmParamCircularFenceEnabledFact, &Fact::rawValueChanged, this, &GeoFenceController::paramCircularFenceChanged); + connect(_apmParamCircularFenceTypeFact, &Fact::rawValueChanged, this, &GeoFenceController::paramCircularFenceChanged); + } + emit paramCircularFenceChanged(); } diff --git a/src/MissionManager/GeoFenceController.h b/src/MissionManager/GeoFenceController.h index 83bb2e253a0..19f06433b2b 100644 --- a/src/MissionManager/GeoFenceController.h +++ b/src/MissionManager/GeoFenceController.h @@ -35,8 +35,8 @@ class GeoFenceController : public PlanElementController Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged) Q_PROPERTY(Fact* breachReturnAltitude READ breachReturnAltitude CONSTANT) - // Hack to expose PX4 circular fence controlled by GF_MAX_HOR_DIST - Q_PROPERTY(double paramCircularFence READ paramCircularFence NOTIFY paramCircularFenceChanged) + // Radius of the "paramCircularFence" which is called the "Geofence Failsafe" in PX4 and the "Circular Geofence" on ArduPilot + Q_PROPERTY(double paramCircularFence READ paramCircularFence NOTIFY paramCircularFenceChanged) /// Add a new inclusion polygon to the fence /// @param topLeft: Top left coordinate or map viewport @@ -114,11 +114,18 @@ private slots: Fact _breachReturnAltitudeFact; double _breachReturnDefaultAltitude = qQNaN(); bool _itemsRequested = false; - Fact* _px4ParamCircularFenceFact = nullptr; + + Fact* _px4ParamCircularFenceFact = nullptr; + Fact* _apmParamCircularFenceRadiusFact = nullptr; + Fact* _apmParamCircularFenceEnabledFact = nullptr; + Fact* _apmParamCircularFenceTypeFact = nullptr; static QMap _metaDataMap; static const char* _px4ParamCircularFence; + static const char* _apmParamCircularFenceRadius; + static const char* _apmParamCircularFenceEnabled; + static const char* _apmParamCircularFenceType; static const int _jsonCurrentVersion = 2; From d5b4de2e09c5d1d5cf313c9d438576c62b1cf8af Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 29 Aug 2023 11:11:32 -0700 Subject: [PATCH 048/118] Change button name when forced to buttons only --- src/VehicleSetup/SetupView.qml | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/VehicleSetup/SetupView.qml b/src/VehicleSetup/SetupView.qml index 715f9b6caf0..cd190b39c63 100644 --- a/src/VehicleSetup/SetupView.qml +++ b/src/VehicleSetup/SetupView.qml @@ -260,12 +260,16 @@ Rectangle { id: joystickButton imageResource: "/qmlimages/Joystick.png" setupIndicator: true - setupComplete: joystickManager.activeJoystick ? joystickManager.activeJoystick.calibrated || joystickManager.activeJoystick.axisCount == 0 : false + setupComplete: _activeJoystick ? _activeJoystick.calibrated || _buttonsOnly : false exclusiveGroup: setupButtonGroup visible: _fullParameterVehicleAvailable && joystickManager.joysticks.length !== 0 - text: qsTr("Joystick") + text: _forcedToButtonsOnly ? qsTr("Buttons") : qsTr("Joystick") Layout.fillWidth: true onClicked: showPanel(this, "JoystickConfig.qml") + + property var _activeJoystick: joystickManager.activeJoystick + property bool _buttonsOnly: _activeJoystick ? _activeJoystick.axisCount == 0 : false + property bool _forcedToButtonsOnly: !QGroundControl.corePlugin.options.allowJoystickSelection && _buttonsOnly } Repeater { From 13abdb072b525270ee6a5a40abcbd77f372523d9 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 1 Sep 2023 10:31:06 +1200 Subject: [PATCH 049/118] Settings/VideoManager: add Herelink video stream This adds two video settings: 1. QGC running on Herelink connecting to the AirUnit. 2. QGC running on any device connected to Herelink's hotspot. By default (without custom build) only 2. is enabled. Signed-off-by: Julian Oes --- src/Settings/VideoSettings.cc | 9 +++++++++ src/Settings/VideoSettings.h | 2 ++ src/VideoManager/VideoManager.cc | 6 ++++++ 3 files changed, 17 insertions(+) diff --git a/src/Settings/VideoSettings.cc b/src/Settings/VideoSettings.cc index 453f37f7fcd..8ade41d1f35 100644 --- a/src/Settings/VideoSettings.cc +++ b/src/Settings/VideoSettings.cc @@ -29,6 +29,8 @@ const char* VideoSettings::videoSourceMPEGTS = QT_TRANSLATE_NOOP("Vid const char* VideoSettings::videoSource3DRSolo = QT_TRANSLATE_NOOP("VideoSettings", "3DR Solo (requires restart)"); const char* VideoSettings::videoSourceParrotDiscovery = QT_TRANSLATE_NOOP("VideoSettings", "Parrot Discovery"); const char* VideoSettings::videoSourceYuneecMantisG = QT_TRANSLATE_NOOP("VideoSettings", "Yuneec Mantis G"); +const char* VideoSettings::videoSourceHerelinkAirUnit = QT_TRANSLATE_NOOP("VideoSettings", "Herelink AirUnit"); +const char* VideoSettings::videoSourceHerelinkHotspot = QT_TRANSLATE_NOOP("VideoSettings", "Herelink Hotspot"); DECLARE_SETTINGGROUP(Video, "Video") { @@ -48,6 +50,13 @@ DECLARE_SETTINGGROUP(Video, "Video") videoSourceList.append(videoSourceParrotDiscovery); videoSourceList.append(videoSourceYuneecMantisG); #endif + +#ifdef QGC_HERELINK_AIRUNIT_VIDEO + videoSourceList.append(videoSourceHerelinkAirUnit); +#else + videoSourceList.append(videoSourceHerelinkHotspot); +#endif + #ifndef QGC_DISABLE_UVC QList cameras = QCameraInfo::availableCameras(); for (const QCameraInfo &cameraInfo: cameras) { diff --git a/src/Settings/VideoSettings.h b/src/Settings/VideoSettings.h index 3a2bd5ea8a5..f9475773b8c 100644 --- a/src/Settings/VideoSettings.h +++ b/src/Settings/VideoSettings.h @@ -73,6 +73,8 @@ class VideoSettings : public SettingsGroup static const char* videoSource3DRSolo; static const char* videoSourceParrotDiscovery; static const char* videoSourceYuneecMantisG; + static const char* videoSourceHerelinkAirUnit; + static const char* videoSourceHerelinkHotspot; signals: void streamConfiguredChanged (bool configured); diff --git a/src/VideoManager/VideoManager.cc b/src/VideoManager/VideoManager.cc index cca88f17911..fd6d90a665b 100644 --- a/src/VideoManager/VideoManager.cc +++ b/src/VideoManager/VideoManager.cc @@ -565,6 +565,8 @@ VideoManager::isGStreamer() videoSource == VideoSettings::videoSource3DRSolo || videoSource == VideoSettings::videoSourceParrotDiscovery || videoSource == VideoSettings::videoSourceYuneecMantisG || + videoSource == VideoSettings::videoSourceHerelinkAirUnit || + videoSource == VideoSettings::videoSourceHerelinkHotspot || autoStreamConfigured(); #else return false; @@ -741,6 +743,10 @@ VideoManager::_updateSettings(unsigned id) settingsChanged |= _updateVideoUri(0, QStringLiteral("udp://0.0.0.0:8888")); else if (source == VideoSettings::videoSourceYuneecMantisG) settingsChanged |= _updateVideoUri(0, QStringLiteral("rtsp://192.168.42.1:554/live")); + else if (source == VideoSettings::videoSourceHerelinkAirUnit) + settingsChanged |= _updateVideoUri(0, QStringLiteral("rtsp://192.168.0.10:8554/H264Video")); + else if (source == VideoSettings::videoSourceHerelinkHotspot) + settingsChanged |= _updateVideoUri(0, QStringLiteral("rtsp://192.168.43.1:8554/fpv_stream")); else if (source == VideoSettings::videoDisabled || source == VideoSettings::videoSourceNoVideo) settingsChanged |= _updateVideoUri(0, ""); else { From bd897577076575a6200055e30484f4ca6094b9ad Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Tue, 5 Sep 2023 15:49:42 +0000 Subject: [PATCH 050/118] Update PX4 Firmware metadata Tue Sep 5 15:49:42 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 55280a109b0..d2e2d7af490 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -8407,6 +8407,10 @@ Enabled + + ASP5033 differential pressure sensor (external I2C) + true + Enable simulated barometer sensor instance 0 @@ -10370,12 +10374,6 @@ 20000 1000000 - - UAVCAN Node ID - Read the specs at http://uavcan.org to learn more about Node ID. - 1 - 125 - Enable MovingBaselineData publication true From ffda931df5a93132d51aae9ca0bd7200f0f6ca2f Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Thu, 7 Sep 2023 19:04:57 +0000 Subject: [PATCH 051/118] Update PX4 Firmware metadata Thu Sep 7 19:04:57 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index d2e2d7af490..9e86625d063 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -9514,11 +9514,10 @@ true - Control the number of distance sensors on the vehicle - If set to the number of distance sensors, the preflight check will check for their presence and valid data publication. Disable with 0 if no distance sensor present or to disable the preflight check. + Number of distance sensors to check being available + The preflight check will fail if fewer than this number of distance sensors with valid data is present. Disable the check with 0. 0 4 - true Enable HITL/SIH mode on next boot From 4b8eee279a101f6f3f475974e6d151da1115ad76 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 13 Sep 2023 15:10:39 +0200 Subject: [PATCH 052/118] fix FirmwarePlugin: increase arming timeout to 1.5s As the arming flag is set from the heartbeat received at 1Hz, we need to wait a bit longer than 1s. The 1s timeout sometimes led to this error message when trying to start a mission: "Unable to start mission: Vehicle rejected arming." Fixes https://github.com/PX4/PX4-Autopilot/issues/22042 --- src/FirmwarePlugin/FirmwarePlugin.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 574f2618f9a..35d44b23492 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -949,8 +949,8 @@ bool FirmwarePlugin::_armVehicleAndValidate(Vehicle* vehicle) // Only try arming the vehicle a single time. Doing retries on arming with a delay can lead to safety issues. vehicle->setArmed(true, false /* showError */); - // Wait 1000 msecs for vehicle to arm - for (int i=0; i<10; i++) { + // Wait 1500 msecs for vehicle to arm (waiting for the next heartbeat) + for (int i = 0; i < 15; i++) { if (vehicle->armed()) { vehicleArmed = true; break; From 736657f461fa66d14d1f061fd9d5d3907a535afc Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Wed, 20 Sep 2023 14:28:08 +0000 Subject: [PATCH 053/118] Update PX4 Firmware metadata Wed Sep 20 14:28:08 UTC 2023 --- .../PX4/PX4ParameterFactMetaData.xml | 116 ++++++++++++------ 1 file changed, 76 insertions(+), 40 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 9e86625d063..d7e60271a4f 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -4051,43 +4051,6 @@ - - X Position of IRLOCK in body frame (forward) - m - 3 - true - - - Y Position of IRLOCK in body frame (right) - m - 3 - true - - - Z Position of IRLOCK in body frame (downward) - m - 3 - true - - - Rotation of IRLOCK sensor relative to airframe - Default orientation of Yaw 90° - -1 - 40 - true - - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - - - - Acceleration uncertainty Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection @@ -4130,6 +4093,41 @@ 0.01 3 + + X Position of IRLOCK in body frame (forward) + m + 3 + true + + + Y Position of IRLOCK in body frame (right) + m + 3 + true + + + Z Position of IRLOCK in body frame (downward) + m + 3 + true + + + Rotation of IRLOCK sensor relative to airframe + Default orientation of Yaw 90° + -1 + 40 + true + + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + + Initial landing target velocity uncertainty Initial variance of the relative landing target velocity in x and y directions @@ -4687,10 +4685,9 @@ 1 - Take-off altitude - This is the minimum altitude the system will take off to. + Default take-off altitude + This is the relative altitude the system will take off to if not otherwise specified. 0 - 80 m 1 0.5 @@ -8305,6 +8302,45 @@ Internal device counter is reset to 0 when overrun this value, counter is able to store up to 6 digits reset of counter takes some time - measurement with reset has worse accuracy. 0 means reset counter after every measurement. true + + AFBR Rangefinder Short/Long Range Threshold Hysteresis + This parameter defines the hysteresis for switching between short and long range mode. + 1 + 10 + m + + + AFBR Rangefinder Long Range Rate + This parameter defines measurement rate of the AFBR Rangefinder in long range mode. + 1 + 100 + + + AFBR Rangefinder Mode + This parameter defines the mode of the AFBR Rangefinder. + 0 + 3 + true + + Short Range Mode + Long Range Mode + High Speed Short Range Mode + High Speed Long Range Mode + + + + AFBR Rangefinder Short Range Rate + This parameter defines measurement rate of the AFBR Rangefinder in short range mode. + 1 + 100 + + + AFBR Rangefinder Short/Long Range Threshold + This parameter defines the threshold for switching between short and long range mode. The mode will switch from short to long range when the distance is greater than the threshold plus the hysteresis. The mode will switch from long to short range when the distance is less than the threshold minus the hysteresis. + 1 + 50 + m + QNH for barometer 500 From 760070636a119eff07df3fba76abe3e7a004de76 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Wed, 20 Sep 2023 16:43:51 +0000 Subject: [PATCH 054/118] Update PX4 Firmware metadata Wed Sep 20 16:43:51 UTC 2023 --- .../PX4/AirframeFactMetaData.xml | 822 +- .../PX4/PX4ParameterFactMetaData.xml | 13533 +++++++++------- 2 files changed, 8755 insertions(+), 5600 deletions(-) diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml index b48dbc49ed3..60bd155a84e 100644 --- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml @@ -6,10 +6,10 @@ Airship Airship - starboard thruster - port thruster - tail thruster - thrust tilt + starboard thruster + port thruster + thrust tilt + tail thruster @@ -18,23 +18,25 @@ ThunderFly s.r.o., Roman Dvorak <dvorakroman@thunderfly.cz> Autogyro https://github.com/ThunderFly-aerospace/Auto-G2/ - throttle - rotor_head_L - rotor_head_R - elevator - rudder - rudder (second, optional) - wheel + rotor_head_L + rotor_head_R + elevator + rudder + rudder (second, optional) + throttle + wheel + feed-through of RC AUX1 channel for prerotator (optional) + feed-through of RC AUX2 channel for release device (optional) Autogyro ThunderFly s.r.o., Roman Dvorak <dvorakroman@thunderfly.cz> Autogyro https://github.com/ThunderFly-aerospace/TF-G2/ - throttle - rotor_head_L - rotor_head_R - rudder + rotor_head_L + rotor_head_R + rudder + throttle @@ -45,17 +47,46 @@ https://github.com/ThunderFly-aerospace/TF-B1/ + + + Copter + Emmanuel Roussel + Coaxial Helicopter + Left swashplate servomotor, pitch axis + Right swashplate servomotor, roll axis + Upper rotor (CCW) + Lower rotor (CW) + + Copter William Peale <develop707@gmail.com> Dodecarotor cox + motor 1 + motor 2 + motor 3 + motor 4 + motor 5 + motor 6 + motor 7 + motor 8 + motor 9 + motor 10 + motor 11 + motor 12 - + Copter + Bart Slinger <bartslinger@gmail.com> Helicopter + main motor + front swashplate servo + right swashplate servo + left swashplate servo + tail-rotor servo @@ -63,6 +94,15 @@ Copter Lorenz Meier <lorenz@px4.io> Hexarotor + + motor1 + motor2 + motor3 + motor4 + motor5 + motor6 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel @@ -70,12 +110,15 @@ Copter Lorenz Meier <lorenz@px4.io> Hexarotor Coaxial - front right top, CW - front right bottom, CCW - back top, CW - back bottom, CCW - front left top, CW - front left bottom, CCW + front right top, CW + front right bottom, CCW + back top, CW + back bottom, CCW + front left top, CW + front left bottom, CCW + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel @@ -83,11 +126,48 @@ Copter Lorenz Meier <lorenz@px4.io> Hexarotor x + motor 1 + motor 2 + motor 3 + motor 4 + motor 5 + motor 6 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel Copter Hyon Lim <lim@uvify.com> Hexarotor x + motor 1 + motor 2 + motor 3 + motor 4 + motor 5 + motor 6 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + + + Copter + Silvan Fuhrer + Hexarotor x + + + + + Copter + Simon Wilks <simon@uaventure.com> + Octo Coax Wide + motor 1 + motor 2 + motor 3 + motor 4 + motor 5 + motor 6 + motor 7 + motor 8 @@ -95,6 +175,17 @@ Copter Lorenz Meier <lorenz@px4.io> Octorotor + + motor 1 + motor 2 + motor 3 + motor 4 + motor 5 + motor 6 + motor 7 + motor 8 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel @@ -102,14 +193,14 @@ Copter Lorenz Meier <lorenz@px4.io> Octorotor Coaxial - motor 1 - motor 2 - motor 3 - motor 4 - motor 5 - motor 6 - motor 7 - motor 8 + motor 1 + motor 2 + motor 3 + motor 4 + motor 5 + motor 6 + motor 7 + motor 8 @@ -117,6 +208,17 @@ Copter Lorenz Meier <lorenz@px4.io> Octorotor x + motor 1 + motor 2 + motor 3 + motor 4 + motor 5 + motor 6 + motor 7 + motor 8 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel @@ -124,6 +226,16 @@ Copter Lorenz Meier <lorenz@px4.io> Quadrotor + + motor 1 + motor 2 + motor 3 + motor 4 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + feed-through of RC FLAPS channel @@ -131,11 +243,95 @@ Copter Blankered Quadrotor H + motor 1 + motor 2 + motor 3 + motor 4 + 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 + + + + + Copter + Lorenz Meier <lorenz@px4.io> + Quadrotor Wide + motor 1 + motor 2 + motor 3 + motor 4 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + feed-through of RC FLAPS channel + + + Copter + Lorenz Meier <lorenz@px4.io> + Quadrotor Wide + motor 1 + motor 2 + motor 3 + motor 4 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + feed-through of RC FLAPS channel + + + Copter + Lorenz Meier <lorenz@px4.io> + Quadrotor Wide + motor 1 + motor 2 + motor 3 + motor 4 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + feed-through of RC FLAPS channel + + + Copter + Simon Wilks <simon@uaventure.com> + Quadrotor Wide + motor 1 + motor 2 + motor 3 + motor 4 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + feed-through of RC FLAPS channel + + + + + Copter + Lorenz Meier <lorenz@px4.io> + Quadrotor asymmetric + https://docs.px4.io/master/en/frames_multicopter/spedix_s250_pixracer.html + motor1 (front right: CCW) + motor2 (back left: CCW) + motor3 (front left: CW) + motor4 (back right: CW) + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel @@ -143,6 +339,36 @@ Copter Lorenz Meier <lorenz@px4.io> Quadrotor x + motor 1 + motor 2 + motor 3 + motor 4 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + feed-through of RC FLAPS channel + + + Copter + James Goppert <james.goppert@gmail.com> + Quadrotor x + + + Copter + Lorenz Meier <lorenz@px4.io> + Quadrotor x + + + Copter + Lorenz Meier <lorenz@px4.io> + Quadrotor x + + + Copter + Lorenz Meier <lorenz@px4.io> + Quadrotor x Copter @@ -154,22 +380,36 @@ Lorenz Meier <lorenz@px4.io> Quadrotor x - + Copter Quadrotor x + motor 1 + motor 2 + motor 3 + motor 4 Copter Iain Galloway <iain.galloway@nxp.com> Quadrotor x + motor 1 + motor 2 + motor 3 + motor 4 - + Copter - Farhang Naderi <farhang.nba@gmail.com> + Silvan Fuhrer Quadrotor x - + Copter + Andreas Antener <andreas@uaventure.com> + Quadrotor x + + + Copter + Lorenz Meier <lorenz@px4.io> Quadrotor x @@ -181,27 +421,72 @@ Copter Beat Kueng <beat-kueng@gmx.net> Quadrotor x - https://docs.px4.io/main/en/frames_multicopter/holybro_qav250_pixhawk4_mini.html + https://docs.px4.io/master/en/frames_multicopter/holybro_qav250_pixhawk4_mini.html Copter Beat Kueng <beat@px4.io> Quadrotor x + + Copter + James Goppert <james.goppert@gmail.com> + Quadrotor x + Copter Quadrotor x + motor 1 + motor 2 + motor 3 + motor 4 Copter Hyon Lim <lim@uvify.com> Quadrotor x + motor 1 + motor 2 + motor 3 + motor 4 + + + Copter + Hyon Lim <lim@uvify.com> + Quadrotor x + motor 1 + motor 2 + motor 3 + motor 4 Copter Hyon Lim <lim@uvify.com> Quadrotor x + motor 1 + motor 2 + motor 3 + motor 4 + + + Copter + Anton Matosov <anton.matosov@gmail.com> + Quadrotor x + + + Copter + Henry Zhang <zhanghui629@gmail.com> + Quadrotor x + + + Copter + Matt McFadden <matt.mcfadden@tealdrones.com> + Quadrotor x + motor 1 + motor 2 + motor 3 + motor 4 Copter @@ -219,7 +504,7 @@ Quadrotor x - + Copter Lorenz Meier <lorenz@px4.io> @@ -231,20 +516,158 @@ Simulation + + + Copter + Ricardo Marques <marques.ricardo17@gmail.com> + Tilt-Quad + http://www.alivaero.com/the-project.html + motor 1 + motor 2 + motor 3 + motor 4 + Outer servo motor for rotor 2 arm + Outer servo motor for rotor 4 arm + Inner servo motor for rotor 2 arm + Inner servo motor for rotor 4 arm + + - + Copter + Trent Lukaczyk <aerialhedgehog@gmail.com> Tricopter Y+ - motor 1 - motor 2 - motor 3 - yaw servo + motor 1 + motor 2 + motor 3 + yaw servo + + + + + Copter + Trent Lukaczyk <aerialhedgehog@gmail.com> + Tricopter Y- + motor 1 + motor 2 + motor 3 + yaw servo - + + Plane + + Flying Wing + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Simon Wilks <simon@uaventure.com> + Flying Wing + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + Plane + Simon Wilks <simon@uaventure.com> Flying Wing + https://docs.px4.io/master/en/frames_plane/wing_wing_z84.html + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Julian Oes <julian@px4.io> + Flying Wing + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Lorenz Meier <lorenz@px4.io> + Flying Wing + https://docs.px4.io/master/en/frames_plane/wing_wing_z84.html + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Simon Wilks <simon@uaventure.com> + Flying Wing + right aileron + left aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Simon Wilks <simon@uaventure.com> + Flying Wing + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Simon Wilks <simon@uaventure.com> + Flying Wing + http://www.sparkletech.hk/ + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Jan Liphardt <JTLiphardt@gmail.com> + Flying Wing + + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Lorenz Meier <lorenz@px4.io> + Flying Wing + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel @@ -252,17 +675,49 @@ Plane Andreas Antener <andreas@uaventure.com> Plane A-Tail - throttle - aileron right - aileron left - v-tail right - v-tail left - wheel - flaps right - flaps left + aileron right + aileron left + v-tail right + v-tail left + throttle + wheel + flaps right + flaps left + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + + + Plane + Friedrich Beckmann <friedrich.beckmann@hs-augsburg.de> + Plane V-Tail + aileron right + aileron left + v-tail right + v-tail left + throttle + wheel + flaps right + flaps left + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel - + + + Plane + Lorenz Meier <lorenz@px4.io> + Simulation + aileron + elevator + rudder + throttle + flaps + gear + Plane Romain Chiappinelli <romain.chiap@gmail.com> @@ -270,30 +725,59 @@ - + Plane + Lorenz Meier <lorenz@px4.io> Standard Plane + aileron + elevator + throttle + rudder + flaps + gear + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Andreas Antener <andreas@uaventure.com> + Standard Plane + aileron + aileron + elevator + rudder + throttle + wheel + flaps + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel - + Rover Rover - throttle - steering + steering + throttle - + Rover + Timothy Scott Rover https://www.aionrobotics.com/r1 + Speed of left wheels + Speed of right wheels Rover Katrin Moritz Rover - Speed of left wheels - Steering servo + Steering servo + Speed of left wheels + Speed of right wheels @@ -313,25 +797,14 @@ Underwater Robot Thies Lennart Alff <thies.lennart.alff@tuhh.de> Vectored 6 DOF UUV - motor 1 CCW, bow starboard horizontal, , propeller CCW - motor 2 CCW, bow port horizontal, propeller CCW - motor 3 CCW, stern starboard horizontal, propeller CW - motor 4 CCW, stern port horizontal, propeller CW - motor 5 CCW, bow starboard vertical, propeller CCW - motor 6 CCW, bow port vertical, propeller CW - motor 7 CCW, stern starboard vertical, propeller CW - motor 8 CCW, stern port vertical, propeller CCW - - - - - VTOL - Romain Chiappinelli <romain.chiap@gmail.com> - Simulation - motor right - motor left - elevon right - elevon left + motor 1 CCW, bow starboard horizontal, , propeller CCW + motor 2 CCW, bow port horizontal, propeller CCW + motor 3 CCW, stern starboard horizontal, propeller CW + motor 4 CCW, stern port horizontal, propeller CW + motor 5 CCW, bow starboard vertical, propeller CCW + motor 6 CCW, bow port vertical, propeller CW + motor 7 CCW, stern starboard vertical, propeller CW + motor 8 CCW, stern port vertical, propeller CCW @@ -340,52 +813,197 @@ Roman Bapst <roman@auterion.com> Standard VTOL - + VTOL + + Standard VTOL + motor 1 + motor 2 + motor 3 + motor 4 + Aileron 1 + Aileron 2 + Elevator + Rudder + Throttle + + + VTOL + Simon Wilks <simon@uaventure.com> + Standard VTOL + motor 1 + motor 2 + motor 3 + motor 4 + Aileron 1 + Aileron 2 + Elevator + Rudder + Throttle + + + VTOL + Simon Wilks <simon@uaventure.com> + Standard VTOL + motor 1 + motor 2 + motor 3 + motor 4 + Right elevon + Left elevon + Motor + + + VTOL + Sander Smeets <sander@droneslab.com> + Standard VTOL + + + VTOL + Sander Smeets <sander@droneslab.com> + Standard VTOL + + + VTOL + Andreas Antener <andreas@uaventure.com> Standard VTOL VTOL Sander Smeets <sander@droneslab.com> Standard VTOL - motor 1 - motor 2 - motor 3 - motor 4 - Right elevon - Left elevon - Pusher motor - Pusher reverse channel + motor 1 + motor 2 + motor 3 + motor 4 + Right elevon + Left elevon + Pusher motor + Pusher reverse channel VTOL Silvan Fuhrer <silvan@auterion.com> Standard VTOL - motor 1 - motor 2 - motor 3 - motor 4 - Pusher motor - Ailerons - A-tail left - A-tail right - - - - + Ailerons + A-tail left + Pusher motor + A-tail right + motor 1 + motor 2 + motor 3 + motor 4 + + + + + VTOL + Roman Bapst <roman@px4.io> + VTOL Duo Tailsitter + motor right + motor left + elevon right + elevon left + + VTOL - VTOL Tailsitter + Roman Bapst <roman@px4.io> + VTOL Duo Tailsitter + motor right + motor left + elevon right + elevon left + + + + + VTOL + VTOL Octoplane + motor 1 + motor 2 + motor 3 + motor 4 + motor 5 + motor 6 + motor 7 + motor 8 + Aileron 1 + Aileron 2 + Elevator + Rudder + Throttle + + + + + VTOL + Roman Bapst <roman@px4.io> + VTOL Quad Tailsitter + + + VTOL + Roman Bapst <roman@px4.io> + VTOL Quad Tailsitter + motor 1 + motor 2 + motor 4 + motor 5 + elevon left + elevon right + canard surface + rudder - + VTOL - + Roman Bapst <roman@uaventure.com> VTOL Tiltrotor + Front right motor bottom + Front right motor top + Back motor bottom + Back motor top + Front left motor bottom + Front left motor top + Tilt servo + Elevon 1 + Elevon 2 + Gear + + + VTOL + Samay Siga <samay_s@icloud.com> + VTOL Tiltrotor + + + VTOL + Andreas Antener <andreas@uaventure.com> + VTOL Tiltrotor + Motor right + Motor left + Motor back + empty + Tilt servo right + Tilt servo left + Elevon right + Elevon left - + VTOL + VTOL Tiltrotor + motor 1 + motor 2 + motor 3 + motor 4 + Motor tilt front left + Motor tilt front right + Motor tilt rear left + Motor tilt rear right + Aileron left + Aileron right + Elevator + Rudder diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index d7e60271a4f..5a80440dbc9 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -196,165 +196,6 @@ us - - - First 4 characters of CALLSIGN - Sets first 4 characters of a total of 8. Valid characters are A-Z, 0-9, " ". Example "PX4 " -> 1347957792 For CALLSIGN shorter than 8 characters use the null terminator at the end '\0'. - true - - - Second 4 characters of CALLSIGN - Sets second 4 characters of a total of 8. Valid characters are A-Z, 0-9, " " only. Example "TEST" -> 1413829460 For CALLSIGN shorter than 8 characters use the null terminator at the end '\0'. - true - - - ADSB-Out Emergency State - Sets the vehicle emergency state - 0 - 6 - false - - NoEmergency - General - Medical - LowFuel - NoCommunications - Interference - Downed - - - - ADSB-Out Vehicle Emitter Type - Configure the emitter type of the vehicle. - 0 - 15 - true - - Unknown - Light - Small - Large - HighVortex - Heavy - Performance - Rotorcraft - RESERVED - Glider - LightAir - Parachute - UltraLight - RESERVED - UAV - Space - RESERVED - EmergencySurf - ServiceSurf - PointObstacle - - - - ADSB-Out GPS Offset lat - Sets GPS lataral offset encoding - 0 - 7 - false - - NoData - LatLeft2M - LatLeft4M - LatLeft6M - LatRight0M - LatRight2M - LatRight4M - LatRight6M - - - - ADSB-Out GPS Offset lon - Sets GPS longitudinal offset encoding - 0 - 1 - false - - NoData - AppliedBySensor - - - - ADSB-Out ICAO configuration - Defines the ICAO ID of the vehicle - -1 - 16777215 - true - - - ADSB-In Special ICAO configuration - This vehicle is always tracked. Use 0 to disable. - 0 - 16777215 - false - - - ADSB-Out Ident Configuration - Enable Identification of Position feature - false - - - ADSB-Out Vehicle Size Configuration - Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size. - 0 - 15 - true - - SizeUnknown - Len15_Wid23 - Len25_Wid28 - Len25_Wid34 - Len35_Wid33 - Len35_Wid38 - Len45_Wid39 - Len45_Wid45 - Len55_Wid45 - Len55_Wid52 - Len65_Wid59 - Len65_Wid67 - Len75_Wid72 - Len75_Wid80 - Len85_Wid80 - Len85_Wid90 - - - - ADSB-In Vehicle List Size - Change number of targets to track - 0 - 50 - true - - - ADSB-Out Vehicle Max Speed - Informs ADSB vehicles of this vehicle's max speed capability - 0 - 6 - true - - UnknownMaxSpeed - 75Kts - 150Kts - 300Kts - 600Kts - 1200Kts - Over1200Kts - - - - ADSB-Out squawk code configuration - This parameter defines the squawk code. Value should be between 0000 and 7777. - 0 - 7777 - false - - Airspeed Selector: Gate size for sideslip angle fusion @@ -369,19 +210,10 @@ 0 1 rad - 3 - + Enable checks on airspeed sensors - Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0. Note that the data missing check is enabled if any of the options is set. - 0 - 15 - - Only data missing check (triggers if more than 1s no data) - Data stuck (triggers if data is exactly constant for 2s in FW mode) - Innovation check (see ASPD_FS_INNOV) - Load factor check (triggers if measurement is below stall speed) - + If set to true then the data comming from the airspeed sensors is checked for validity. Only applied if ASPD_PRIMARY > 0. Enable fallback to sensor-less airspeed estimation @@ -391,21 +223,17 @@ Enable fallback to sensor-less estimation - - Airspeed failure innovation threshold - This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed) and measured airspeed. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter. + + Airspeed failsafe consistency threshold + This specifies the minimum airspeed test ratio required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Start with a value of 1.0 when tuning. When tas_test_ratio is > 1.0 it indicates the inconsistency between predicted and measured airspeed is large enough to cause the wind EKF to reject airspeed measurements. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter. 0.5 - 10.0 - m/s - 1 + 3.0 - - Airspeed failure innovation integral threshold - This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe. Larger values make the check less sensitive, smaller positive values make it more sensitive. - 0.0 - 50.0 - m - 1 + + Airspeed failsafe consistency delay + This sets the time integral of airspeed test ratio exceedance above ASPD_FS_INNOV required to trigger a failsafe. For example if ASPD_FS_INNOV is 1 and estimator_status.tas_test_ratio is 2.0, then the exceedance is 1.0 and the integral will rise at a rate of 1.0/second. A negative value disables the check. Larger positive values make the check less sensitive, smaller positive values make it more sensitive. + 30.0 + s Airspeed failsafe start delay @@ -432,45 +260,22 @@ Third airspeed sensor - - Scale of airspeed sensor 1 - This is the scale IAS --> CAS of the first airspeed sensor instance - 0.5 - 2.0 - 2 - true - - - Scale of airspeed sensor 2 - This is the scale IAS --> CAS of the second airspeed sensor instance - 0.5 - 2.0 - 2 - true - - - Scale of airspeed sensor 3 - This is the scale IAS --> CAS of the third airspeed sensor instance + + Airspeed scale (scale from IAS to CAS) + Scale can either be entered manually, or estimated in-flight by setting ASPD_SCALE_EST to 1. 0.5 - 2.0 - 2 - true + 1.5 - - Controls when to apply the new estimated airspeed scale(s) - - Do not automatically apply the estimated scale - Apply the estimated scale after disarm - Apply the estimated scale in air - + + Automatic airspeed scale estimation on + Turns the automatic airspeed scale (scale from IAS to CAS) on or off. It is recommended to fly level altitude while performing the estimation. Set to 1 to start estimation (best when already flying). Set to 0 to end scale estimation. The estimated scale is then saved using the ASPD_SCALE parameter. - - Airspeed Selector: Wind estimator true airspeed scale process noise spectral density - Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second. + + Airspeed Selector: Wind estimator true airspeed scale process noise + Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. 0 0.1 - 1/s/sqrt(Hz) - 5 + Hz Airspeed Selector: Gate size for true airspeed fusion @@ -485,27 +290,164 @@ 0 4 m/s - 1 - - - Horizontal wind uncertainty threshold for synthetic airspeed - The synthetic airspeed estimate (from groundspeed and heading) will be declared valid as soon and as long the horizontal wind uncertainty drops below this value. - 0.001 - 5 - m/s - 3 - - Airspeed Selector: Wind estimator wind process noise noise spectral density - Wind process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. + + Airspeed Selector: Wind estimator wind process noise + Wind process noise of the internal wind estimator(s) of the airspeed selector. 0 1 - m/s^2/sqrt(Hz) + m/s^2 + + + + + Body X axis angular velocity D gain + Body X axis angular velocity differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + 0.0 + 2.0 + 4 + 0.01 + + + Body X axis angular velocity feedforward gain + Improves tracking performance. + 0.0 + Nm/(rad/s) + 4 + + + Body X axis angular velocity I gain + Body X axis angular velocity integral gain. Can be set to compensate static thrust difference or gravity center offset. + 0.0 + Nm/rad + 3 + 0.01 + + + Body X axis angular velocity integrator limit + Body X axis angular velocity integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes. + 0.0 + Nm + 2 + 0.01 + + + Body X axis angular velocity controller gain + Global gain of the controller. This gain scales the P, I and D terms of the controller: output = AVC_X_K * (AVC_X_P * error + AVC_X_I * error_integral + AVC_X_D * error_derivative) Set AVC_X_P=1 to implement a PID in the ideal form. Set AVC_X_K=1 to implement a PID in the parallel form. + 0.0 + 5.0 + 4 + 0.0005 + + + Body X axis angular velocity P gain + Body X axis angular velocity proportional gain, i.e. control output for angular speed error 1 rad/s. + 0.0 + 20.0 + 1/s + 3 + 0.01 + + + Body Y axis angular velocity D gain + Body Y axis angular velocity differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + 0.0 + 2.0 + 4 + 0.01 + + + Body Y axis angular velocity feedforward + Improves tracking performance. + 0.0 + Nm/(rad/s) + 4 + + + Body Y axis angular velocity I gain + Body Y axis angular velocity integral gain. Can be set to compensate static thrust difference or gravity center offset. + 0.0 + Nm/rad + 3 + 0.01 + + + Body Y axis angular velocity integrator limit + Body Y axis angular velocity integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes. + 0.0 + Nm + 2 + 0.01 + + + Body Y axis angular velocity controller gain + Global gain of the controller. This gain scales the P, I and D terms of the controller: output = AVC_Y_K * (AVC_Y_P * error + AVC_Y_I * error_integral + AVC_Y_D * error_derivative) Set AVC_Y_P=1 to implement a PID in the ideal form. Set AVC_Y_K=1 to implement a PID in the parallel form. + 0.0 + 20.0 + 4 + 0.0005 + + + Body Y axis angular velocity P gain + Body Y axis angular velocity proportional gain, i.e. control output for angular speed error 1 rad/s. + 0.0 + 20.0 + 1/s + 3 + 0.01 + + + Body Z axis angular velocity D gain + Body Z axis angular velocity differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + 0.0 + 2.0 + 2 + 0.01 + + + Body Z axis angular velocity feedforward + Improves tracking performance. + 0.0 + Nm/(rad/s) + 4 + 0.01 + + + Body Z axis angular velocity I gain + Body Z axis angular velocity integral gain. Can be set to compensate static thrust difference or gravity center offset. + 0.0 + Nm/rad + 2 + 0.01 + + + Body Z axis angular velocity integrator limit + Body Z axis angular velocity integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes. + 0.0 + Nm + 2 + 0.01 + + + Body Z axis angular velocity controller gain + Global gain of the controller. This gain scales the P, I and D terms of the controller: output = AVC_Z_K * (AVC_Z_P * error + AVC_Z_I * error_integral + AVC_Z_D * error_derivative) Set AVC_Z_P=1 to implement a PID in the ideal form. Set AVC_Z_K=1 to implement a PID in the parallel form. + 0.0 + 5.0 + 4 + 0.0005 + + + Body Z axis angular velocity P gain + Body Z axis angular velocity proportional gain, i.e. control output for angular speed error 1 rad/s. + 0.0 + 20.0 + 1/s 2 + 0.01 - + Acceleration compensation based on GPS velocity @@ -560,95 +502,212 @@ 2 - - - Controls when to apply the new gains - After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. - - Do not apply the new gains (logging only) - Apply the new gains after disarm - Apply the new gains in air - + + + Battery 1 current per volt (A/V) + The voltage seen by the ADC multiplied by this factor will determine the battery current. A value of -1 means to use the board default. + 8 + True - - Tuning axes selection - Defines which axes will be tuned during the auto-tuning sequence Set bits in the following positions to enable: 0 : Roll 1 : Pitch 2 : Yaw - 1 - 7 - - roll - pitch - yaw - + + Battery 1 capacity + Defines the capacity of battery 1 in mAh. + -1.0 + 100000 + mAh + 0 + 50 + True + + + Battery 1 Current ADC Channel + This parameter specifies the ADC channel used to monitor current of main power battery. A value of -1 means to use the board default. + True + + + Number of cells for battery 1 + Defines the number of cells the attached battery consists of. + True + + 2S Battery + 3S Battery + 4S Battery + 5S Battery + 6S Battery + 7S Battery + 8S Battery + 9S Battery + 10S Battery + 11S Battery + 12S Battery + 13S Battery + 14S Battery + 15S Battery + 16S Battery + + + + Explicitly defines the per cell internal resistance for battery 1 + If non-negative, then this will be used in place of BAT1_V_LOAD_DROP for all calculations. + -1.0 + 0.2 + Ohm + 2 + 0.01 + True - - Enable/disable auto tuning using an RC AUX input - Defines which RC_MAP_AUXn parameter maps the RC channel used to enable/disable auto tuning. - 0 - 6 + + Battery 1 monitoring source + This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current. + True - Disable - Aux1 - Aux2 - Aux3 - Aux4 - Aux5 - Aux6 + Disabled + Power Module + External + ESCs - - Start the autotuning sequence - WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using FW_AT_SYSID_AMP for more signal/noise ratio + + Battery 1 Voltage ADC Channel + This parameter specifies the ADC channel used to monitor voltage of main power battery. A value of -1 means to use the board default. + True - - Amplitude of the injected signal - This parameter scales the signal sent to the rate controller during system identification. - 0.1 - 6.0 - 1 + + Full cell voltage (5C load) + Defines the voltage where a single cell of battery 1 is considered full under a mild load. This will never be the nominal voltage of 4.2V + V + 2 + 0.01 + True + + + Battery 1 voltage divider (V divider) + This is the divider from battery 1 voltage to ADC voltage. If using e.g. Mauch power modules the value from the datasheet can be applied straight here. A value of -1 means to use the board default. + 8 + True + + + Empty cell voltage (5C load) + Defines the voltage where a single cell of battery 1 is considered empty. The voltage should be chosen before the steep dropoff to 2.8V. A typical lithium battery can only be discharged down to 10% before it drops off to a voltage level damaging the cells. + V + 2 + 0.01 + True - - Controls when to apply the new gains - After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. WARNING Applying the gains in air is dangerous as there is no guarantee that those new gains will be able to stabilize the drone properly. + + Voltage drop per cell on full throttle + This implicitely defines the internal resistance to maximum current ratio for battery 1 and assumes linearity. A good value to use is the difference between the 5C and 20-25C load. Not used if BAT1_R_INTERNAL is set. + 0.07 + 0.5 + V + 2 + 0.01 + True + + + Battery 2 current per volt (A/V) + The voltage seen by the ADC multiplied by this factor will determine the battery current. A value of -1 means to use the board default. + 8 + True + + + Battery 2 capacity + Defines the capacity of battery 2 in mAh. + -1.0 + 100000 + mAh + 0 + 50 + True + + + Battery 2 Current ADC Channel + This parameter specifies the ADC channel used to monitor current of main power battery. A value of -1 means to use the board default. + True + + + Number of cells for battery 2 + Defines the number of cells the attached battery consists of. + True + + 2S Battery + 3S Battery + 4S Battery + 5S Battery + 6S Battery + 7S Battery + 8S Battery + 9S Battery + 10S Battery + 11S Battery + 12S Battery + 13S Battery + 14S Battery + 15S Battery + 16S Battery + + + + Explicitly defines the per cell internal resistance for battery 2 + If non-negative, then this will be used in place of BAT2_V_LOAD_DROP for all calculations. + -1.0 + 0.2 + Ohm + 2 + 0.01 + True + + + Battery 2 monitoring source + This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current. + True - Do not apply the new gains (logging only) - Apply the new gains after disarm - WARNING Apply the new gains in air + Disabled + Power Module + External + ESCs - - Multicopter autotune module enable + + Battery 2 Voltage ADC Channel + This parameter specifies the ADC channel used to monitor voltage of main power battery. A value of -1 means to use the board default. + True - - Desired angular rate closed-loop rise time - 0.01 - 0.5 - s + + Full cell voltage (5C load) + Defines the voltage where a single cell of battery 1 is considered full under a mild load. This will never be the nominal voltage of 4.2V + V 2 + 0.01 + True - - Start the autotuning sequence - WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using MC_AT_SYSID_AMP for more signal/noise ratio + + Battery 2 voltage divider (V divider) + This is the divider from battery 2 voltage to ADC voltage. If using e.g. Mauch power modules the value from the datasheet can be applied straight here. A value of -1 means to use the board default. + 8 + True - - Amplitude of the injected signal - 0.1 - 6.0 - 1 + + Empty cell voltage (5C load) + Defines the voltage where a single cell of battery 1 is considered empty. The voltage should be chosen before the steep dropoff to 2.8V. A typical lithium battery can only be discharged down to 10% before it drops off to a voltage level damaging the cells. + V + 2 + 0.01 + True + + + Voltage drop per cell on full throttle + This implicitely defines the internal resistance to maximum current ratio for battery 1 and assumes linearity. A good value to use is the difference between the 5C and 20-25C load. Not used if BAT2_R_INTERNAL is set. + 0.07 + 0.5 + V + 2 + 0.01 + True - - This parameter is deprecated. Please use BAT1_I_CHANNEL - - Expected battery current in flight - This value is used to initialize the in-flight average current estimation, which in turn is used for estimating remaining flight time and RTL triggering. - 0 - 500 - A - 0.1 - Critical threshold Sets the threshold when the battery will be reported as critically low. This has to be lower than the low threshold. This threshold commonly will trigger RTL. @@ -682,7 +741,7 @@ This parameter is deprecated. Please use BAT1_V_CHARGED instead - + This parameter is deprecated. Please use BAT1_V_EMPTY instead @@ -790,6 +849,22 @@ Distance based, on command (Survey mode) + + Camera trigger pin + Selects which FMU pin is used (range: AUX1-AUX8 on Pixhawk controllers with an I/O board, MAIN1-MAIN8 on controllers without an I/O board). The PWM interface takes two pins per camera, while relay triggers on every pin individually. Example: Value 56 would trigger on pins 5 and 6. For GPIO mode Pin 6 will be triggered followed by 5. With a value of 65 pin 5 will be triggered followed by 6. Pins may be non contiguous. I.E. 16 or 61. In GPIO mode the delay pin to pin is < .2 uS. + 1 + 12345678 + 0 + true + + + Camera trigger pin extended + This Bit mask selects which FMU pin is used (range: AUX9-AUX32) If the value is not 0 it takes precedence over TRIG_PINS. If bits above 8 are set that value is used as the selector for trigger pins. greater then 8. 0x00000300 Would be Pins 9,10. If the value is + 0 + 2147483647 + 0 + true + Camera trigger polarity This parameter sets the polarity of the trigger (0 = active low, 1 = active high ) @@ -831,7 +906,14 @@ 782097 true - + + Circuit breaker for engine failure detection + Setting this parameter to 284953 will disable the engine failure detection. If the aircraft is in engine failure mode the engine failure flag will be set to healthy WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK + 0 + 284953 + true + + Circuit breaker for flight termination Setting this parameter to 121212 will disable the flight termination action if triggered by the FailureDetector logic or if FMU is lost. This circuit breaker does not affect the RC loss, data link loss, geofence, and takeoff failure detection safety logic. 0 @@ -844,6 +926,13 @@ 0 22027 + + Circuit breaker for rate controller output + Setting this parameter to 140253 will disable the rate controller uORB publication. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK + 0 + 140253 + true + Circuit breaker for power supply check Setting this parameter to 894281 will disable the power valid checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK @@ -856,6 +945,12 @@ 0 197848 + + Circuit breaker for position error check + Setting this parameter to 201607 will disable the position and velocity accuracy checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK + 0 + 201607 + Circuit breaker for arming in fixed-wing mode check Setting this parameter to 159753 will enable arming in fixed-wing mode for VTOLs. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK @@ -864,25 +959,12 @@ - - Set the actuator failure failsafe mode - Note: actuator failure needs to be enabled and configured via FD_ACT_* parameters. - 0 - 3 - - Warning only - Hold mode - Land mode - Return mode - Terminate - - - - Flag to allow arming - Set 0 to prevent accidental use of the vehicle e.g. for safety or maintenance reasons. + + Enable preflight check for maximal allowed airspeed when arming + Deny arming if the current airspeed measurement is greater than half the cruise airspeed (FW_AIRSPD_TRIM). Excessive airspeed measurements on ground are either caused by wind or bad airspeed calibration. - Disallow arming - Allow arming + Disabled + Enabled @@ -940,10 +1022,6 @@ 2 0.05 - - Enable FMU SD card hardfault detection check - This check detects if there are hardfault files present on the SD card. If so, and the parameter is enabled, arming is prevented. - Maximum accelerometer inconsistency between IMU units that will allow arming 0.1 @@ -960,35 +1038,21 @@ 3 0.01 - + Maximum magnetic field inconsistency between units that will allow arming Set -1 to disable the check. 3 180 deg - + Enable mag strength preflight check - Check if the estimator detects a strong magnetic disturbance (check enabled by EKF2_MAG_CHECK) - - Disabled - Deny arming - Warning only - + Deny arming if the estimator detects a strong magnetic disturbance (check enabled by EKF2_MAG_CHECK) Require valid mission to arm The default allows to arm the vehicle without a valid mission. - - Enable Drone ID system detection and health check - This check detects if the Open Drone ID system is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming. - - Disabled - Warning only - Enforce Open Drone ID system presence - - Enable FMU SD card detection check This check detects if the FMU SD card is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming. @@ -1004,12 +1068,13 @@ Allow arming without GPS + The default allows the vehicle to arm without GPS signal. Require GPS lock to arm Allow arming without GPS - + Maximum allowed CPU load to still arm A negative value disables the check. -1 @@ -1021,32 +1086,49 @@ Time-out for auto disarm after landing A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. A zero or negative value means that automatic disarming triggered by landing detection is disabled. s - 1 - 0.1 + 2 Time-out for auto disarm if not taking off A non-zero, positive value specifies the time in seconds, within which the vehicle is expected to take off after arming. In case the vehicle didn't takeoff within the timeout it disarms again. A negative value disables autmoatic disarming triggered by a pre-takeoff timeout. s - 1 - 0.1 + 2 - GCS connection loss time threshold - After this amount of seconds without datalink, the GCS connection lost mode triggers + Datalink loss time threshold + After this amount of seconds without datalink the data link lost mode triggers 5 300 s 1 1 - - Delay between failsafe condition triggered and failsafe reaction - Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode for the user to realize. During that time the user cannot take over control via the stick override feature see COM_RC_OVERRIDE. Afterwards the configured failsafe action is triggered and the user may use stick override. A zero value disables the delay and the user cannot take over via stick movements (switching modes is still allowed). + + Engine Failure Current/Throttle Threshold + Engine failure triggers only below this current value 0.0 - 25.0 + 50.0 + A/% + 2 + 1 + + + Engine Failure Throttle Threshold + Engine failure triggers only above this throttle value + 0.0 + 1.0 + norm + 2 + 0.01 + + + Engine Failure Time Threshold + Engine failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time + 0.0 + 60.0 s - 3 + 1 + 1 Next flight UUID @@ -1070,7 +1152,6 @@ Takeoff Land Follow Me - Precision Land @@ -1090,7 +1171,6 @@ Takeoff Land Follow Me - Precision Land @@ -1110,7 +1190,6 @@ Takeoff Land Follow Me - Precision Land @@ -1130,7 +1209,6 @@ Takeoff Land Follow Me - Precision Land @@ -1150,7 +1228,6 @@ Takeoff Land Follow Me - Precision Land @@ -1170,7 +1247,6 @@ Takeoff Land Follow Me - Precision Land @@ -1183,16 +1259,6 @@ Developer - - Maximum allowed flight time - The vehicle aborts the current operation and returns to launch when the time since takeoff is above this value. It is not possible to resume the mission or switch to any auto mode other than RTL or Land. Taking over in any manual mode is still possible. Starting from 90% of the maximum flight time, a warning message will be sent every 1 minute with the remaining time until automatic RTL. Set to -1 to disable. - -1 - s - - - Enable force safety - Force safety when the vehicle disarms - High Latency Datalink loss time threshold After this amount of seconds without datalink the data link lost mode triggers @@ -1207,25 +1273,27 @@ 60 s - - Home position enabled - Set home position automatically if possible. - true + + Home set horizontal threshold + The home position will be set if the estimated positioning accuracy is below the threshold. + 2 + 15 + m + 2 + 0.5 Allows setting the home position after takeoff If set to true, the autopilot is allowed to set its home position after takeoff The true home position is back-computed if a local position is estimate if available. If no local position is available, home is set to the current position. - - Imbalanced propeller failsafe mode - Action the system takes when an imbalanced propeller is detected by the failure detector. See also FD_IMB_PROP_THR to set the failure threshold. - 1 - - Disabled - Warning - Return - Land - + + Home set vertical threshold + The home position will be set if the estimated positioning accuracy is below the threshold. + 5 + 25 + m + 2 + 0.5 Timeout value for disarming when kill switch is engaged @@ -1236,7 +1304,7 @@ Timeout for detecting a failure after takeoff - A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to disarm the vehicle if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW). A zero or negative value means that the check is disabled. + A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to put the vehicle into a lockdown state if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW). A zero or negative value means that the check is disabled. -1.0 5.0 s @@ -1245,6 +1313,8 @@ Battery failsafe mode Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR for definition of battery states. + 0 + 1 Warning Land mode @@ -1252,8 +1322,8 @@ - Enable Actuator Testing - If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that allows spinning the motors and moving the servos for testing purposes. + Enable Motor Testing + If set, enables the motor test interface via MAVLink (DO_MOTOR_TEST), that allows spinning the motors for testing purposes. Time-out to wait when onboard computer connection is lost before warning about loss connection @@ -1262,10 +1332,23 @@ s 0.01 - + Set offboard loss failsafe mode The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. + Disabled + Land mode + Hold mode + Return mode + Terminate + Lockdown + + + + Set offboard loss failsafe mode when RC is available + The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. + + Disabled Position mode Altitude mode Manual @@ -1273,7 +1356,7 @@ Land mode Hold mode Terminate - Disarm + Lockdown @@ -1281,21 +1364,18 @@ Time-out to wait when offboard connection is lost before triggering offboard lost action - See COM_OBL_RC_ACT to configure action. + See COM_OBL_ACT and COM_OBL_RC_ACT to configure action. 0 60 s 0.01 - - Expect and require a healthy MAVLink parachute system - Position control navigation loss response - This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control. If Altitude/Manual is selected: assume use of remote control after fallback. Switch to Altitude mode if a height estimate is available, else switch to MANUAL. If Land/Descend is selected: assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to Descend. + This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control. Navigation accuracy checks can be disabled using the CBRK_VELPOSERR parameter, but doing so will remove protection for all flight modes. - Altitude/Manual - Land/Descend + Altitude/Manual. Assume use of remote control after fallback. Switch to Altitude mode if a height estimate is available, else switch to MANUAL. + Land/Terminate. Assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to TERMINATION. @@ -1305,21 +1385,28 @@ 100 s - + Horizontal position error threshold - This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous position error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). Set to -1 to disable. - -1 - 400 + This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. m - 1 - - EPH threshold for RTL - Specify the threshold for triggering a warning for low local position accuracy. Additionally triggers a RTL if currently in Mission or Loiter mode. Local position has to be still declared valid, which is most of all depending on COM_POS_FS_EPH. Use this feature on systems with dead-reckoning capabilites (e.g. fixed-wing vehicles with airspeed sensor) to improve the user notification and failure mitigation when flying in GNSS-denied areas. Set to -1 to disable. - -1 - 1000 + + Vertical position error threshold + This is the vertical position error (EPV) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. m + + Loss of position probation gain factor + This sets the rate that the loss of position probation time grows when position checks are failing. The default value has been optimised for rotary wing applications. For fixed wing applications a value of 0 should be used. + true + + + Loss of position probation delay at takeoff + The probation delay is the number of seconds that the EKF innovation checks need to pass for the position to be declared good after it has been declared bad. The probation delay will be reset to this parameter value when takeoff is detected. After takeoff, if position checks are passing, the probation delay will reduce by one second for every lapsed second of valid position down to a minimum of 1 second. If position checks are failing, the probation delay will increase by COM_POS_FS_GAIN seconds for every lapsed second up to a maximum of 100 seconds. The default value has been optimised for rotary wing applications. For fixed wing applications, a value of 1 should be used. + 1 + 100 + s + Required number of redundant power modules This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected. Note: CBRK_SUPPLY_CHK disables all power checks including this one. @@ -1335,14 +1422,13 @@ Always - - Set command after a quadchute - - Warning only - Return mode - Land mode - Hold mode - + + Delay between RC loss and configured reaction + RC signal not updated -> still use data for COM_RC_LOSS_T seconds Consider RC signal lost -> wait COM_RCL_ACT_T seconds on the spot waiting to regain signal React with failsafe action NAV_RCL_ACT A zero value disables the delay. + 0.0 + 25.0 + s + 3 RC loss exceptions @@ -1362,17 +1448,15 @@ 1500 ms - + RC control input mode - A value of 0 enables RC transmitter control (only). A valid RC transmitter calibration is required. A value of 1 allows joystick control only. RC input handling and the associated checks are disabled. A value of 2 allows either RC Transmitter or Joystick input. The first valid input is used, will fallback to other sources if the input stream becomes invalid. A value of 3 allows either input from RC or joystick. The first available source is selected and used until reboot. A value of 4 ignores any stick input. + The default value of 0 requires a valid RC transmitter setup. Setting this to 1 allows joystick control and disables RC input handling and the associated checks. A value of 2 will generate RC control data from manual input received via MAVLink instead of directly forwarding the manual input data. 0 - 4 + 2 - RC Transmitter only - Joystick only - RC and Joystick with fallback - RC or Joystick keep first - Stick input disabled + RC Transmitter + Joystick/No RC Checks + Virtual RC by Joystick @@ -1386,12 +1470,13 @@ Enable RC stick override of auto and/or offboard modes - When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV immediately gives control back to the pilot by switching to Position mode and if position is unavailable Altitude mode. Note: Only has an effect on multicopters, and VTOLs in multicopter mode. + When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV from their center position immediately gives control back to the pilot by switching to Position mode. Note: Only has an effect on multicopters, and VTOLs in multicopter mode. 0 - 3 + 7 Enable override during auto modes (except for in critical battery reaction) Enable override during offboard mode + Ignore throttle stick @@ -1403,14 +1488,9 @@ 0 0.05 - - Enforced delay between arming and further navigation - The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds. Goal: - Motors and propellers spool up to idle speed before getting commanded to spin faster - Timeout for ESCs and smart batteries to successfulyy do failure checks e.g. for stuck rotors before the vehicle is off the ground - 0 - 30 - s - 1 - 0.1 + + Rearming grace period + Re-arming grace allows to rearm the drone with manual command without running prearmcheck during 5 s after disarming. Action after TAKEOFF has been accepted @@ -1420,32 +1500,14 @@ Mission (if valid) - + Horizontal velocity error threshold - This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous velocity error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). - 0 + This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. m/s - 1 - - - Wind speed RTL threshold - Wind speed threshold above which an automatic return to launch is triggered. It is not possible to resume the mission or switch to any auto mode other than RTL or Land if this threshold is exceeded. Taking over in any manual mode is still possible. Set to -1 to disable. - -1 - m/s - 1 - 0.1 - - - Wind speed warning threshold - A warning is triggered if the currently estimated wind speed is above this value. Warning is sent periodically (every 1 minute). Set to -1 to disable. - -1 - m/s - 1 - 0.1 - Set GCS connection loss failsafe mode - The GCS connection loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed. + Set data link loss failsafe mode + The data link loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed. 0 6 @@ -1454,7 +1516,7 @@ Return mode Land mode Terminate - Disarm + Lockdown @@ -1467,210 +1529,544 @@ Return mode Land mode Terminate - Disarm + Lockdown + + Maximum allowed RTL flight in minutes + This is used to determine when the vehicle should be switched to RTL due to low battery. Note, particularly for multirotors this should reflect flight time at cruise speed, not while stationary + min + - - - UAVCAN/CAN v1 bus bitrate - 20000 - 1000000 - bit/s - true + + + Maximum value for actuator 0 - - Cyphal - 0 - Cyphal disabled. 1 - Enables Cyphal - true + + Minimum value for actuator 0 - - Cyphal Node ID - Read the specs at http://uavcan.org to learn more about Node ID. - -1 - 125 - true + + Maximum value for actuator 10 - - actuator_outputs uORB over Cyphal publication port ID - -1 - 6143 + + Minimum value for actuator 10 - - UDRAL battery parameters subscription port ID - -1 - 6143 + + Maximum value for actuator 11 - - UDRAL battery status subscription port ID - -1 - 6143 + + Minimum value for actuator 11 - - UDRAL battery energy source subscription port ID - -1 - 6143 + + Maximum value for actuator 12 - - ESC 0 subscription port ID - -1 - 6143 + + Minimum value for actuator 12 - - Cyphal ESC publication port ID - -1 - 6143 + + Maximum value for actuator 13 - - GPS 0 subscription port ID - -1 - 6143 + + Minimum value for actuator 13 - - GPS 1 subscription port ID - -1 - 6143 + + Maximum value for actuator 14 - - Cyphal GPS publication port ID - -1 - 6143 + + Minimum value for actuator 14 - - Cyphal legacy battery port ID - -1 - 6143 + + Maximum value for actuator 15 - - Cyphal Servo publication port ID - -1 - 6143 + + Minimum value for actuator 15 - - sensor_gps uORB over Cyphal subscription port ID - -1 - 6143 + + Maximum value for actuator 1 - - sensor_gps uORB over Cyphal publication port ID - -1 - 6143 + + Minimum value for actuator 1 - - - - 1-sigma IMU accelerometer switch-on bias - 0.0 - 0.5 - m/s^2 - 2 - true + + Maximum value for actuator 2 - - Maximum IMU accel magnitude that allows IMU bias learning - If the magnitude of the IMU accelerometer vector exceeds this value, the EKF delta velocity state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the delta velocity bias estimates. - 20.0 - 200.0 - m/s^2 - 1 + + Minimum value for actuator 2 - - Maximum IMU gyro angular rate magnitude that allows IMU bias learning - If the magnitude of the IMU angular rate vector exceeds this value, the EKF delta velocity state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the delta velocity bias estimates. - 2.0 - 20.0 - rad/s - 1 + + Maximum value for actuator 3 - - Accelerometer bias learning limit - The ekf delta velocity bias states will be limited to within a range equivalent to +- of this value. - 0.0 - 0.8 - m/s^2 - 2 + + Minimum value for actuator 3 - - Time constant used by acceleration and angular rate magnitude checks used to inhibit delta velocity bias learning - The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay. - 0.1 - 1.0 - s - 2 + + Maximum value for actuator 4 - - Process noise for IMU accelerometer bias prediction - 0.0 - 0.01 - m/s^3 - 6 + + Minimum value for actuator 4 - - Accelerometer noise for covariance prediction - 0.01 - 1.0 - m/s^2 - 2 + + Maximum value for actuator 5 - - Will be removed after v1.14 release - Set bits in the following positions to enable: 0 : Deprecated, use EKF2_GPS_CTRL instead 1 : Deprecated. use EKF2_OF_CTRL instead 2 : Deprecated, use EKF2_IMU_CTRL instead 3 : Deprecated, use EKF2_EV_CTRL instead 4 : Deprecated, use EKF2_EV_CTRL instead 5 : Deprecated. use EKF2_DRAG_CTRL instead 6 : Deprecated, use EKF2_EV_CTRL instead 7 : Deprecated, use EKF2_GPS_CTRL instead 8 : Deprecated, use EKF2_EV_CTRL instead - 0 - 511 - true - - unused - unused - unused - unused - unused - unused - unused - unused - unused - + + Minimum value for actuator 5 - - 1-sigma tilt angle uncertainty after gravity vector alignment - 0.0 - 0.5 - rad - 3 - true + + Maximum value for actuator 6 - - Airspeed fusion threshold - A value of zero will deactivate airspeed fusion. Any other positive value will determine the minimum airspeed which will still be fused. Set to about 90% of the vehicles stall speed. Both airspeed fusion and sideslip fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_FUSE_BETA to activate sideslip fusion. Note: side slip fusion is currently not supported for tailsitters. - 0.0 - m/s - 1 + + Minimum value for actuator 6 - - Upper limit on airspeed along individual axes used to correct baro for position error effects - 5.0 - 50.0 - m/s - 1 + + Maximum value for actuator 7 - - Airspeed measurement delay relative to IMU measurements - 0 - 300 - ms - 1 - true + + Minimum value for actuator 7 - - Auxiliary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements + + Maximum value for actuator 8 + + + Minimum value for actuator 8 + + + Maximum value for actuator 9 + + + Minimum value for actuator 9 + + + Airframe ID + This is used to retrieve pre-computed control effectiveness matrix + 0 + 2 + + Multirotor + Standard VTOL (WIP) + Tiltrotor VTOL (WIP) + + + + Airspeed scaler + This compensates for the variation of flap effectiveness with airspeed. + + + Battery power level scaler + This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery. + + + Axis of rotor 0 thrust vector, X body axis component + + + Axis of rotor 0 thrust vector, Y body axis component + + + Axis of rotor 0 thrust vector, Z body axis component + + + Thrust coefficient of rotor 0 + The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT0_MIN and CA_ACT0_MAX) is the output signal sent to the motor controller. + + + Moment coefficient of rotor 0 + The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. + + + Position of rotor 0 along X body axis + + + Position of rotor 0 along Y body axis + + + Position of rotor 0 along Z body axis + + + Axis of rotor 1 thrust vector, X body axis component + + + Axis of rotor 1 thrust vector, Y body axis component + + + Axis of rotor 1 thrust vector, Z body axis component + + + Thrust coefficient of rotor 1 + The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT1_MIN and CA_ACT1_MAX) is the output signal sent to the motor controller. + + + Moment coefficient of rotor 1 + The moment coefficient if defined as Torque = KM * Thrust, Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. + + + Position of rotor 1 along X body axis + + + Position of rotor 1 along Y body axis + + + Position of rotor 1 along Z body axis + + + Axis of rotor 2 thrust vector, X body axis component + + + Axis of rotor 2 thrust vector, Y body axis component + + + Axis of rotor 2 thrust vector, Z body axis component + + + Thrust coefficient of rotor 2 + The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT2_MIN and CA_ACT2_MAX) is the output signal sent to the motor controller. + + + Moment coefficient of rotor 2 + The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. + + + Position of rotor 2 along X body axis + + + Position of rotor 2 along Y body axis + + + Position of rotor 2 along Z body axis + + + Axis of rotor 3 thrust vector, X body axis component + + + Axis of rotor 3 thrust vector, Y body axis component + + + Axis of rotor 3 thrust vector, Z body axis component + + + Thrust coefficient of rotor 3 + The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT3_MIN and CA_ACT3_MAX) is the output signal sent to the motor controller. + + + Moment coefficient of rotor 3 + The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. + + + Position of rotor 3 along X body axis + + + Position of rotor 3 along Y body axis + + + Position of rotor 3 along Z body axis + + + Axis of rotor 4 thrust vector, X body axis component + + + Axis of rotor 4 thrust vector, Y body axis component + + + Axis of rotor 4 thrust vector, Z body axis component + + + Thrust coefficient of rotor 4 + The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT4_MIN and CA_ACT4_MAX) is the output signal sent to the motor controller. + + + Moment coefficient of rotor 4 + The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. + + + Position of rotor 4 along X body axis + + + Position of rotor 4 along Y body axis + + + Position of rotor 4 along Z body axis + + + Axis of rotor 5 thrust vector, X body axis component + + + Axis of rotor 5 thrust vector, Y body axis component + + + Axis of rotor 5 thrust vector, Z body axis component + + + Thrust coefficient of rotor 5 + The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT5_MIN and CA_ACT5_MAX) is the output signal sent to the motor controller. + + + Moment coefficient of rotor 5 + The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. + + + Position of rotor 5 along X body axis + + + Position of rotor 5 along Y body axis + + + Position of rotor 5 along Z body axis + + + Axis of rotor 6 thrust vector, X body axis component + + + Axis of rotor 6 thrust vector, Y body axis component + + + Axis of rotor 6 thrust vector, Z body axis component + + + Thrust coefficient of rotor 6 + The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT6_MIN and CA_ACT6_MAX) is the output signal sent to the motor controller. + + + Moment coefficient of rotor 6 + The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. + + + Position of rotor 6 along X body axis + + + Position of rotor 6 along Y body axis + + + Position of rotor 6 along Z body axis + + + Axis of rotor 7 thrust vector, X body axis component + + + Axis of rotor 7 thrust vector, Y body axis component + + + Axis of rotor 7 thrust vector, Z body axis component + + + Thrust coefficient of rotor 7 + The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT7_MIN and CA_ACT7_MAX) is the output signal sent to the motor controller. + + + Moment coefficient of rotor 7 + The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. + + + Position of rotor 7 along X body axis + + + Position of rotor 7 along Y body axis + + + Position of rotor 7 along Z body axis + + + Control allocation method + 0 + 1 + + Pseudo-inverse with output clipping (default) + Pseudo-inverse with sequential desaturation technique + + + + + + DSHOT 3D deadband high + When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin. This value is with respect to the mixer_module range (0-1999), not the DSHOT values. + 1000 + 1999 + + + DSHOT 3D deadband low + When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin. This value is with respect to the mixer_module range (0-1999), not the DSHOT values. + 0 + 1000 + + + Allows for 3d mode when using DShot and suitable mixer + WARNING: ESC must be configured for 3D mode, and DSHOT_MIN set to 0. This splits the throttle ranges in two. Direction 1) 48 is the slowest, 1047 is the fastest. Direction 2) 1049 is the slowest, 2047 is the fastest. When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent. + + + Configure DShot + This enables/disables DShot. The different modes define different speeds, for example DShot150 = 150kb/s. Not all ESCs support all modes. Note: this enables DShot on the FMU outputs. For boards with an IO it is the AUX outputs. + True + + Disable (use PWM/Oneshot) + DShot150 + DShot300 + DShot600 + DShot1200 + + + + Minimum DShot Motor Output + Minimum Output Value for DShot in percent. The value depends on the ESC. Make sure to set this high enough so that the motors are always spinning while armed. + 0 + 1 + % + 2 + 0.01 + + + Serial Configuration for DShot Driver + Configure on which serial port to run DShot Driver. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + + + + Number of magnetic poles of the motors + Specify the number of magnetic poles of the motors. It is required to compute the RPM value from the eRPM returned with the ESC telemetry. Either get the number from the motor spec sheet or count the magnets on the bell of the motor (not the stator magnets). Typical motors for 5 inch props have 14 poles. + + + + + Airfield home alt + Altitude of airfield home waypoint + -50 + m + 1 + 0.5 + + + Airfield home Lat + Latitude of airfield home waypoint + -900000000 + 900000000 + deg*1e7 + + + Airfield home Lon + Longitude of airfield home waypoint + -1800000000 + 1800000000 + deg*1e7 + + + + + 1-sigma IMU accelerometer switch-on bias + 0.0 + 0.5 + m/s^2 + 2 + true + + + Maximum IMU accel magnitude that allows IMU bias learning + If the magnitude of the IMU accelerometer vector exceeds this value, the EKF delta velocity state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the delta velocity bias estimates. + 20.0 + 200.0 + m/s^2 + 1 + + + Maximum IMU gyro angular rate magnitude that allows IMU bias learning + If the magnitude of the IMU angular rate vector exceeds this value, the EKF delta velocity state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the delta velocity bias estimates. + 2.0 + 20.0 + rad/s + 1 + + + Accelerometer bias learning limit + The ekf delta velocity bias states will be limited to within a range equivalent to +- of this value. + 0.0 + 0.8 + m/s^2 + 2 + + + Time constant used by acceleration and angular rate magnitude checks used to inhibit delta velocity bias learning + The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay. + 0.1 + 1.0 + s + 2 + + + Process noise for IMU accelerometer bias prediction + 0.0 + 0.01 + m/s^3 + 6 + + + Accelerometer noise for covariance prediction + 0.01 + 1.0 + m/s^2 + 2 + + + Integer bitmask controlling data fusion and aiding methods + Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU delta velocity bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion. Cannot be used if bit position 7 is true. 5 : Set to true to enable multi-rotor drag specific force fusion 6 : set to true if the EV observations are in a non NED reference frame and need to be rotated before being used 7 : Set to true to enable GPS yaw fusion. Cannot be used if bit position 4 is true. + 0 + 511 + true + + use GPS + use optical flow + inhibit IMU bias estimation + vision position fusion + vision yaw fusion + multi-rotor drag fusion + rotate external vision + GPS yaw fusion + vision velocity fusion + + + + 1-sigma tilt angle uncertainty after gravity vector alignment + 0.0 + 0.5 + rad + 3 + true + + + Airspeed fusion threshold + A value of zero will deactivate airspeed fusion. Any other positive value will determine the minimum airspeed which will still be fused. Set to about 90% of the vehicles stall speed. Both airspeed fusion and sideslip fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_FUSE_BETA to activate sideslip fusion. + 0.0 + m/s + 1 + + + Upper limit on airspeed along individual axes used to correct baro for position error effects + 5.0 + 50.0 + m/s + 1 + + + Airspeed measurement delay relative to IMU measurements 0 300 ms 1 true - - Barometric sensor height aiding - If this parameter is enabled then the estimator will make use of the barometric height measurements to estimate its height in addition to other height sources (if activated). + + Auxillary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements + 0 + 300 + ms + 1 + true Barometer measurement delay relative to IMU measurements @@ -1696,7 +2092,7 @@ X-axis ballistic coefficient used for multi-rotor wind estimation - This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis. + This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The EKF2_BCOEF_X paraemter should be set initially to the ratio of mass / projected frontal area and adjusted together with EKF2_MCOEF to minimise variance of the X-axis drag specific force innovation sequence. The drag produced by this effect scales with speed squared. Set this parameter to zero to turn off the bluff body drag model for this axis. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. 0.0 200.0 kg/m^2 @@ -1704,7 +2100,7 @@ Y-axis ballistic coefficient used for multi-rotor wind estimation - This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis. + This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The EKF2_BCOEF_Y paraemter should be set initially to the ratio of mass / projected side area and adjusted together with EKF2_MCOEF to minimise variance of the Y-axis drag specific force innovation sequence. The drag produced by this effect scales with speed squared. et this parameter to zero to turn off the bluff body drag model for this axis. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. 0.0 200.0 kg/m^2 @@ -1736,10 +2132,6 @@ use declination as an observation - - Multirotor wind estimation selection - Activate wind speed estimation using specific-force measurements and a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles that have their thrust aligned with the Z axis and no thrust in the XY plane. - Specific drag force observation noise variance used by the multi-rotor specific drag force model Increasing this makes the multi-rotor wind estimates adjust more slowly. @@ -1755,7 +2147,7 @@ m/s 1 - + Measurement noise for vision angle observations used to lower bound or replace the uncertainty included in the message 0.05 rad @@ -1787,19 +2179,7 @@ m/s 2 - - External vision (EV) sensor aiding - Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw - 0 - 15 - - Horizontal position - Vertical position - 3D velocity - Yaw - - - + Vision Position Estimator delay relative to IMU measurements 0 300 @@ -1807,13 +2187,9 @@ 1 true - - External vision (EV) noise mode - If set to 0 (default) the measurement noise is taken from the vision message and the EV noise parameters are used as a lower bound. If set to 1 the observation noise is set from the parameters directly, - - EV reported variance (parameter lower bound) - EV noise parameters - + + Whether to set the external vision observation noise from the parameter or from vision message + If set to true the observation noise is set from the parameters directly, if set to false the measurement noise is taken from the vision message and the parameter are used as a lower bound. X position of VI sensor focal point in body frame (forward axis with origin relative to vehicle centre of gravity) @@ -1830,13 +2206,6 @@ m 3 - - External vision (EV) minimum quality (optional) - External vision will only be started and fused if the quality metric is above this threshold. The quality metric is a completely optional field provided by some VIO systems. - 0 - 100 - 1 - Boolean determining if synthetic sideslip measurements should fused A value of 1 indicates that fusion is active Both sideslip fusion and airspeed fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_ARSP_THR to activate airspeed fusion. @@ -1867,7 +2236,7 @@ Integer bitmask controlling GPS checks - Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Maximum allowed PDOP set by EKF2_REQ_PDOP 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT + Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Maximum allowed PDOP set by EKF2_REQ_PDOP 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT 0 511 @@ -1882,18 +2251,6 @@ Max vertical velocity discrepancy (EKF2_REQ_VDRIFT) - - GNSS sensor aiding - Set bits in the following positions to enable: 0 : Longitude and latitude fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading fusion - 0 - 15 - - Lon/lat - Altitude - 3D velocity - Dual antenna heading - - GPS measurement delay relative to IMU measurements 0 @@ -1945,29 +2302,14 @@ m/s 2 - - Accelerometer measurement noise for gravity based observations - 0.1 - 10.0 - m/s^2 - 2 - Default value of true airspeed used in EKF-GSF AHRS calculation - If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes. + If no airspeed measurements are avalable, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes. 0.0 100.0 m/s 1 - - Gyro bias learning limit - The ekf delta angle bias states will be limited to within a range equivalent to +- of this value. - 0.0 - 0.4 - rad/s - 3 - Process noise for IMU rate gyro bias prediction 0.0 @@ -1983,7 +2325,7 @@ 4 - Gate size for heading fusion + Gate size for magnetic heading fusion Sets the number of standard deviations used by the innovation consistency test. 1.0 SD @@ -1996,9 +2338,9 @@ rad 2 - - Determines the reference source of height data used by the EKF - When multiple height sources are enabled at the same time, the height estimate will always converge towards the reference height source selected by this parameter. The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. + + Determines the primary source of height data used by the EKF + The range sensor option should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. true Barometric pressure @@ -2007,16 +2349,6 @@ Vision - - IMU control - 0 - 7 - - Gyro Bias - Accel Bias - Gravity vector fusion - - X position of IMU in body frame (forward axis with origin relative to vehicle centre of gravity) m @@ -2034,7 +2366,7 @@ Horizontal acceleration threshold used by automatic selection of magnetometer fusion method - This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered horizontal acceleration is greater than this parameter value, then the EKF will use 3-axis magnetometer fusion. + This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered horizontal acceleration is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion. 0.0 5.0 m/s^2 @@ -2047,32 +2379,9 @@ gauss/s 6 - + Magnetic field strength test selection - Bitmask to set which check is used to decide whether the magnetometer data is valid. If GNSS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find the theoretical strength and inclination using the WMM - 0 - 7 - - Strength (EKF2_MAG_CHK_STR) - Inclination (EKF2_MAG_CHK_INC) - Wait for WMM - - - - Magnetic field inclination check tolerance - Maximum allowed deviation from the expected magnetic field inclination to pass the check. - 0.0 - 90.0 - deg - 1 - - - Magnetic field strength check tolerance - Maximum allowed deviation from the expected magnetic field strength to pass the check. - 0.0 - 1.0 - gauss - 2 + When set, the EKF checks the strength of the magnetic field to decide whether the magnetometer data is valid. If GPS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. Magnetic declination @@ -2110,37 +2419,55 @@ Type of magnetometer fusion - Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight with fallback to magnetic heading fusion if there is insufficient motion to make yaw or magnetic field states observable. If set to 'Magnetic heading' magnetic heading fusion is used at all times. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality). + Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fuson of magnetomer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight with fallback to magnetic heading fusion if there is insufficient motion to make yaw or magnetic field states observable. If set to 'Magnetic heading' magnetic heading fusion is used at all times If set to '3-axis' 3-axis field fusion is used at all times. If set to 'VTOL custom' the behaviour is the same as 'Automatic', but if fusing airspeed, magnetometer fusion is only allowed to modify the magnetic field states. This can be used by VTOL platforms with large magnetic field disturbances to prevent incorrect bias states being learned during forward flight operation which can adversely affect estimation accuracy after transition to hovering flight. If set to 'MC custom' the behaviour is the same as 'Automatic, but if there are no earth frame position or velocity observations being used, the magnetometer will not be used. This enables vehicles to operate with no GPS in environments where the magnetic field cannot be used to provide a heading reference. Prior to flight, the yaw angle is assumed to be constant if movement tests controlled by the EKF2_MOVE_TEST parameter indicate that the vehicle is static. This allows the vehicle to be placed on the ground to learn the yaw gyro bias prior to flight. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality). Other external sources of yaw may be used if selected via the EKF2_AID_MASK parameter. true Automatic Magnetic heading + 3-axis + VTOL custom + MC custom None - + Yaw rate threshold used by automatic selection of magnetometer fusion method - This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered yaw rate is greater than this parameter value, then the EKF will use 3-axis magnetometer fusion. + This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered yaw rate is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion. 0.0 1.0 rad/s 2 - Propeller momentum drag coefficient used for multi-rotor wind estimation - This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. Set this parameter to zero to turn off the momentum drag model for both axis. + propeller momentum drag coefficient used for multi-rotor wind estimation + This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. For example, if flying at 10 m/s at sea level conditions produces a rotor induced drag deceleration of 1.5 m/s/s when the multi-copter levelled to zero roll/pitch, then EKF2_MCOEF would be set to 0.15 = (1.5/10.0). Set EKF2_MCOEF to a positive value to enable wind estimation using this drag effect. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. The EKF2_MCOEF parameter should be adjusted together with EKF2_BCOEF_X and EKF2_BCOEF_Y to minimise variance of the X and y axis drag specific force innovation sequences. 0 1.0 1/s 2 - - Expected range finder reading when on ground - If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground. - 0.01 - m + + Minimum time of arrival delta between non-IMU observations before data is downsampled + Baro and Magnetometer data will be averaged before downsampling, other data will be point sampled resulting in loss of information. + 10 + 50 + ms + true + + + Expected range finder reading when on ground + If the vehicle is on ground, is not moving as determined by the motion test controlled by EKF2_MOVE_TEST and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is avilable at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground. + 0.01 + m 2 + + Vehicle movement test threshold + Scales the threshold tests applied to IMU data used to determine if the vehicle is static or moving. See parameter descriptions for EKF2_GPS_CHECK and EKF2_MAG_TYPE for further information on the functionality affected by this parameter. + 0.1 + 10.0 + 1 + Multi-EKF IMUs Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. Requires SENS_IMU_MODE 0. @@ -2168,10 +2495,6 @@ 10000000 us - - Optical flow aiding - Enable optical flow fusion. - Optical flow measurement delay relative to IMU measurements Assumes measurement is timestamped at trailing edge of integration period @@ -2217,12 +2540,7 @@ 3 - Optical Flow data will only be used in air if the sensor reports a quality metric >= EKF2_OF_QMIN - 0 - 255 - - - Optical Flow data will only be used on the ground if the sensor reports a quality metric >= EKF2_OF_QMIN_GND + Optical Flow data will only be used if the sensor reports a quality metric >= EKF2_OF_QMIN 0 255 @@ -2261,13 +2579,6 @@ 0.5 2 - - EKF prediction period - EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. Actual filter update will be an integer multiple of IMU update. - 1000 - 20000 - us - Required EPH to use GPS 2 @@ -2322,9 +2633,17 @@ m/s 2 + + Range sensor aid + If this parameter is enabled then the estimator will make use of the range finder measurements to estimate it's height even if range sensor is not the primary height source. It will only do so if conditions for range measurement fusion are met. This enables the range finder to be used during low speed and low altitude operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX. If vehicle motion causes repeated switching between the primary height sensor and range finder, an offset in the local position origin can accumulate. Also range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. + + Range aid disabled + Range aid enabled + + - Maximum absolute altitude (height above ground level) allowed for conditional range aid mode - If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). + Maximum absolute altitude (height above ground level) allowed for range aid mode + If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled). 1.0 10.0 m @@ -2337,21 +2656,12 @@ SD - Maximum horizontal velocity allowed for conditional range aid mode - If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). + Maximum horizontal velocity allowed for range aid mode + If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled). 0.1 2 m/s - - Range sensor height aiding - WARNING: Range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. To en-/disable range finder for terrain height estimation, use EKF2_TERR_MASK instead. If this parameter is enabled then the estimator will make use of the range finder measurements to estimate its height in addition to other height sources (if activated). Range sensor aiding can be enabled (i.e.: always use) or set in "conditional" mode. Conditional mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX. - - Disable range fusion - Enabled (conditional mode) - Enabled - - Range finder measurement delay relative to IMU measurements 0 @@ -2367,13 +2677,6 @@ SD 1 - - Gate size used for range finder kinematic consistency check - To be used, the time derivative of the distance sensor measurements projected on the vertical axis needs to be statistically consistent with the estimated vertical velocity of the drone. Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate. - 0.1 - 5.0 - SD - Measurement noise for range finder fusion 0.01 @@ -2409,7 +2712,7 @@ s - Range finder range dependent noise scaler + Range finder range dependant noise scaler Specifies the increase in range finder noise with range. 0.0 0.2 @@ -2441,7 +2744,7 @@ Enable synthetic magnetometer Z component measurement - Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value. + Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ingored instead of fusing the synthetic value. Gate size for TAS fusion @@ -2485,12 +2788,11 @@ m/s 1 - - Process noise spectral density for wind velocity prediction - When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. + + Process noise for wind velocity prediction 0.0 1.0 - m/s^2/sqrt(Hz) + m/s^2 3 @@ -2524,178 +2826,452 @@ - - Maximum manual pitch angle - Maximum manual pitch angle setpoint (positive & negative) in manual attitude-only stabilized mode - 0.0 - 90.0 + + Acro body x max rate + This is the rate the controller is trying to achieve if the user applies full roll stick input in acro mode. + 45 + 720 deg - 1 - 0.5 - - Maximum manual roll angle - Maximum manual roll angle setpoint (positive & negative) in manual attitude-only stabilized mode - 0.0 - 90.0 + + Acro body y max rate + This is the body y rate the controller is trying to achieve if the user applies full pitch stick input in acro mode. + 45 + 720 deg - 1 - 0.5 - - - Maximum manually added yaw rate - This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode. The controller already generates a yaw rate setpoint to coordinate a turn, and this value is added to it. This is an absolute value, which is applied symmetrically to the negative and positive side. - 0 - deg/s - 1 - 0.5 - - Pitch setpoint offset (pitch at level flight) - An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the pitch at typical cruise speed of the airframe. - -90.0 - 90.0 + + Acro body z max rate + This is the body z rate the controller is trying to achieve if the user applies full yaw stick input in acro mode. + 10 + 180 deg - 1 - 0.5 - - Maximum negative / down pitch rate setpoint + + Airspeed mode + For small wings or VTOL without airspeed sensor this parameter can be used to enable flying without an airspeed reading + + Normal (use airspeed if available) + Airspeed disabled + + + + Enable airspeed scaling + This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro) + + + Whether to scale throttle by battery power level + This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The fixed wing should constantly behave as if it was fully charged with reduced max thrust at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery. + + + Pitch trim increment for flaps configuration + This increment is added to the pitch trim whenever flaps are fully deployed. + -0.25 + 0.25 + 2 + 0.01 + + + Pitch trim increment at maximum airspeed + This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX. + -0.25 + 0.25 + 2 + 0.01 + + + Pitch trim increment at minimum airspeed + This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN. + -0.25 + 0.25 + 2 + 0.01 + + + Roll trim increment for flaps configuration + This increment is added to TRIM_ROLL whenever flaps are fully deployed. + -0.25 + 0.25 + 2 + 0.01 + + + Roll trim increment at maximum airspeed + This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX. + -0.25 + 0.25 + 2 + 0.01 + + + Roll trim increment at minimum airspeed + This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN. + -0.25 + 0.25 + 2 + 0.01 + + + Yaw trim increment at maximum airspeed + This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX. + -0.25 + 0.25 + 2 + 0.01 + + + Yaw trim increment at minimum airspeed + This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN. + -0.25 + 0.25 + 2 + 0.01 + + + Scale factor for flaperons 0.0 - 180 - deg/s - 1 - 0.5 + 1.0 + norm + 2 + 0.01 - - Maximum positive / up pitch rate setpoint + + Flaps setting during landing + Sets a fraction of full flaps (FW_FLAPS_SCL) during landing 0.0 - 180 - deg/s - 1 - 0.5 + 1.0 + norm + 2 + 0.01 - - Attitude pitch time constant - This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed. - 0.2 + + Scale factor for flaps + 0.0 1.0 - s + norm 2 - 0.05 + 0.01 - - Maximum roll rate setpoint + + Flaps setting during take-off + Sets a fraction of full flaps (FW_FLAPS_SCL) during take-off 0.0 - 180 - deg/s + 1.0 + norm + 2 + 0.01 + + + Max manual pitch + Max pitch for manual control in attitude stabilized mode + 0.0 + 90.0 + deg 1 0.5 - - Attitude Roll Time Constant - This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed. - 0.2 - 1.0 - s + + Manual pitch scale + Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. + 0.0 + norm 2 - 0.05 + 0.01 + + + Max manual roll + Max roll for manual control in attitude stabilized mode + 0.0 + 90.0 + deg + 1 + 0.5 - - Spoiler descend setting + + Manual roll scale + Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. 0.0 1.0 norm 2 0.01 - - Spoiler landing setting + + Manual yaw scale + Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. 0.0 - 1.0 norm 2 0.01 - - Wheel steering rate feed forward + + Pitch rate feed forward Direct feed forward from rate setpoint to control surface output 0.0 - 10 + 10.0 %/rad/s 2 0.05 - - Wheel steering rate integrator gain + + Pitch rate integrator gain This gain defines how much control response will result out of a steady state error. It trims any constant error. - 0.0 - 10 + 0.005 + 0.5 %/rad 3 0.005 - - Wheel steering rate integrator limit + + Pitch rate integrator limit The portion of the integrator part in the control surface deflection is limited to this value 0.0 1.0 2 0.05 - - Wheel steering rate proportional gain - This defines how much the wheel steering input will be commanded depending on the current body angular rate error. - 0.0 - 10 + + Pitch rate proportional gain + This defines how much the elevator input will be commanded depending on the current body angular rate error. + 0.005 + 1.0 %/rad/s 3 0.005 - - Enable wheel steering controller - Only enabled during automatic runway takeoff and landing. In all manual modes the wheel is directly controlled with yaw stick. + + Pitch setpoint offset (pitch at level flight) + An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the pitch at typical cruise speed of the airframe. + -90.0 + 90.0 + deg + 1 + 0.5 - - Maximum wheel steering rate - This limits the maximum wheel steering rate the controller will output (in degrees per second). + + Maximum negative / down pitch rate + This limits the maximum pitch down up angular rate the controller will output (in degrees per second). 0.0 90.0 deg/s 1 0.5 - - Maximum yaw rate setpoint + + Maximum positive / up pitch rate + This limits the maximum pitch up angular rate the controller will output (in degrees per second). 0.0 - 180 + 90.0 deg/s 1 0.5 - - - - Bit mask to set the automatic landing abort conditions - Terrain estimation: bit 0: Abort if terrain is not found bit 1: Abort if terrain times out (after a first successful measurement) The last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the selected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored. TODO: Extend automatic abort conditions e.g. glide slope tracking error (horizontal and vertical) - 0 - 3 - - Abort if terrain is not found (only applies to mission landings) - Abort if terrain times out (after a first successful measurement) - + + Attitude pitch time constant + This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed. + 0.2 + 1.0 + s + 2 + 0.05 - - Landing airspeed - The calibrated airspeed setpoint during landing. If set <= 0.0, landing airspeed = FW_AIRSPD_MIN by default. - -1.0 - m/s + + Roll control to yaw control feedforward gain + This gain can be used to counteract the "adverse yaw" effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator (rudder, airbrakes, ...) to counteract this effect. + 0.0 1 - 0.1 + 0.01 + + + Roll rate feed forward + Direct feed forward from rate setpoint to control surface output. Use this to obtain a tigher response of the controller without introducing noise amplification. + 0.0 + 10.0 + %/rad/s + 2 + 0.05 + + + Roll rate integrator Gain + This gain defines how much control response will result out of a steady state error. It trims any constant error. + 0.005 + 0.2 + %/rad + 3 + 0.005 + + + Roll integrator anti-windup + The portion of the integrator part in the control surface deflection is limited to this value. + 0.0 + 1.0 + 2 + 0.05 + + + Roll rate proportional Gain + This defines how much the aileron input will be commanded depending on the current body angular rate error. + 0.005 + 1.0 + %/rad/s + 3 + 0.005 + + + Maximum roll rate + This limits the maximum roll rate the controller will output (in degrees per second). + 0.0 + 90.0 + deg/s + 1 + 0.5 + + + Attitude Roll Time Constant + This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed. + 0.4 + 1.0 + s + 2 + 0.05 + + + Wheel steering rate feed forward + Direct feed forward from rate setpoint to control surface output + 0.0 + 10.0 + %/rad/s + 2 + 0.05 + + + Wheel steering rate integrator gain + This gain defines how much control response will result out of a steady state error. It trims any constant error. + 0.005 + 0.5 + %/rad + 3 + 0.005 + + + Wheel steering rate integrator limit + The portion of the integrator part in the control surface deflection is limited to this value + 0.0 + 1.0 + 2 + 0.05 + + + Wheel steering rate proportional gain + This defines how much the wheel steering input will be commanded depending on the current body angular rate error. + 0.005 + 1.0 + %/rad/s + 3 + 0.005 + + + Enable wheel steering controller + + + Maximum wheel steering rate + This limits the maximum wheel steering rate the controller will output (in degrees per second). + 0.0 + 90.0 + deg/s + 1 + 0.5 + + + Yaw rate feed forward + Direct feed forward from rate setpoint to control surface output + 0.0 + 10.0 + %/rad/s + 2 + 0.05 + + + Yaw rate integrator gain + This gain defines how much control response will result out of a steady state error. It trims any constant error. + 0.0 + 50.0 + %/rad + 1 + 0.5 + + + Yaw rate integrator limit + The portion of the integrator part in the control surface deflection is limited to this value + 0.0 + 1.0 + 2 + 0.05 + + + Yaw rate proportional gain + This defines how much the rudder input will be commanded depending on the current body angular rate error. + 0.005 + 1.0 + %/rad/s + 3 + 0.005 + + + Maximum yaw rate + This limits the maximum yaw rate the controller will output (in degrees per second). + 0.0 + 90.0 + deg/s + 1 + 0.5 + + + + + Climbout Altitude difference + If the altitude error exceeds this parameter, the system will climb out with maximum throttle and minimum airspeed until it is closer than this distance to the desired altitude. Mostly used for takeoff waypoints / modes. Set to 0 to disable climbout mode (not recommended). + 0.0 + 150.0 + m + 1 + 0.5 + + + L1 damping + Damping factor for L1 control. + 0.6 + 0.9 + 2 + 0.05 + + + L1 period + This is the L1 distance and defines the tracking point ahead of the aircraft its following. A value of 18-25 meters works for most aircraft. Shorten slowly during tuning until response is sharp without oscillation. + 12.0 + 50.0 + m + 1 + 0.5 + + + L1 controller roll slew rate limit + The maxium change in roll angle setpoint per second. + 0 + deg/s + 1 + + + Min. airspeed scaling factor for landing + Multiplying this factor with the minimum airspeed of the plane gives the target airspeed the landing approach. FW_AIRSPD_MIN * FW_LND_AIRSPD_SC + 1.0 + 1.5 + norm + 2 + 0.01 - Maximum landing slope angle - Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled. Set this value within the vehicle's performance limits. + Landing slope angle 1.0 15.0 deg @@ -2706,17 +3282,17 @@ Early landing configuration deployment When disabled, the landing configuration (flaps, landing airspeed, etc.) is only activated on the final approach to landing. When enabled, it is already activated when entering the final loiter-down (loiter-to-alt) waypoint before the landing approach. This shifts the (often large) altitude and airspeed errors caused by the configuration change away from the ground such that these are not so critical. It also gives the controller enough time to adapt to the new configuration such that the landing approach starts with a cleaner initial state. - + Landing flare altitude (relative to landing altitude) - NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * |z-velocity|) is taken as the flare altitude 0.0 + 25.0 m 1 0.5 Flare, maximum pitch - Maximum pitch during flare, a positive sign means nose up Applied once flaring is triggered + Maximum pitch during flare, a positive sign means nose up Applied once FW_LND_FLALT is reached 0 45.0 deg @@ -2725,227 +3301,146 @@ Flare, minimum pitch - Minimum pitch during flare, a positive sign means nose up Applied once flaring is triggered - -5 + Minimum pitch during flare, a positive sign means nose up Applied once FW_LND_FLALT is reached + 0 15.0 deg 1 0.5 - - Landing flare sink rate - TECS will attempt to control the aircraft to this sink rate via pitch angle (throttle killed during flare) - 0.0 - 2 - m/s - 2 - 0.1 - - - Landing flare time - Multiplied by the descent rate to calculate a dynamic altitude at which to trigger the flare. NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * descent rate) is taken as the flare altitude - 0.1 - 5.0 - s - 1 - 0.1 - - - Landing touchdown nudging option - Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant Approach path nudging: shifts the touchdown point laterally along with the entire approach path This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the desired landing vector. Nuding is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle). + + Landing heading hold horizontal distance + Set to 0 to disable heading hold. 0 - 2 - - Disable nudging - Nudge approach angle - Nudge approach path - - - - Maximum lateral position offset for the touchdown point - 0.0 - 10.0 + 30.0 m 1 - 1 + 0.5 - - Landing touchdown time (since flare start) - This is the time after the start of flaring that we expect the vehicle to touch the runway. At this time, a 0.5s clamp down ramp will engage, constraining the pitch setpoint to RWTO_PSP. If enabled, ensure that RWTO_PSP is configured appropriately for full gear contact on ground roll. Set to -1.0 to disable touchdown clamping. E.g. it may not be desirable to clamp on belly landings. The touchdown time will be constrained to be greater than or equal to the flare time (FW_LND_FL_TIME). - -1.0 - 5.0 - s + + FW_LND_HVIRT + 1.0 + 15.0 + m 1 - 0.1 + 0.5 Altitude time constant factor for landing - Set this parameter to less than 1.0 to make TECS react faster to altitude errors during landing than during normal flight. During landing, the TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value. + Set this parameter to less than 1.0 to make TECS react faster to altitude errors during landing than during normal flight (i.e. giving efficiency and low motor wear at high altitudes but control accuracy during landing). During landing, the TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value. 0.2 1.0 0.1 - - Use terrain estimation during landing. This is critical for detecting when to flare, and should be enabled if possible - NOTE: terrain estimate is currently solely derived from a distance sensor. If enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing will be aborted, depending on the criteria set in FW_LND_ABORT. If disabled, FW_LND_ABORT terrain based criteria are ignored. + + Landing throttle limit altitude (relative landing altitude) + Default of -1.0 lets the system default to applying throttle limiting at 2/3 of the flare altitude. + -1.0 + 30.0 + m + 1 + 0.5 + + + Use terrain estimate during landing + This is turned off by default and a waypoint or return altitude is normally used (or sea level for an arbitrary land position). + + + RC stick mapping fixed-wing + Set RC/joystick configuration for fixed-wing position and altitude controlled flight. 0 - 2 + 1 - Disable the terrain estimate - Use the terrain estimate to trigger the flare (only) - Calculate landing glide slope relative to the terrain estimate + Normal stick configuration (airspeed on throttle stick, altitude on pitch stick) + Alternative stick configuration (altitude on throttle stick, airspeed on pitch stick) - - - - Height (AGL) of the wings when the aircraft is on the ground - This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer to give a slight margin here (> 0m) + + Positive pitch limit + The maximum positive pitch the controller will output. 0.0 - m + 60.0 + deg 1 - 1 + 0.5 - - The aircraft's wing span (length from tip to tip) - This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span) - 0.1 - m + + Negative pitch limit + The minimum negative pitch the controller will output. + -60.0 + 0.0 + deg 1 - 0.1 - - - - - Trigger time - Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds. - 0.0 - 5.0 - s - 2 - 0.05 + 0.5 - - Trigger acceleration threshold - Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds. - 0 - m/s^2 + + Controller roll limit + The maximum roll the controller will output. + 35.0 + 65.0 + deg 1 0.5 - - FW Launch detection - Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles. Only available for fixed-wing vehicles. Not compatible with runway takeoff. - - - Motor delay - Start the motor(s) this amount of seconds after launch is detected. + + Scale throttle by pressure change + Automatically adjust throttle to account for decreased air density at higher altitudes. Start with a scale factor of 1.0 and adjust for different propulsion systems. When flying without airspeed sensor this will help to keep a constant performance over large altitude ranges. The default value of 0 will disable scaling. 0.0 10.0 - s 1 - 0.5 + 0.1 - - - - NPFG damping ratio - Damping ratio of the NPFG control law. - 0.10 - 1.00 + + Cruise throttle + This is the throttle setting required to achieve the desired cruise speed. Most airframes have a value of 0.5-0.7. + 0.0 + 1.0 + norm 2 0.01 - - Enable minimum forward ground speed maintaining excess wind handling logic - - - Maximum, minimum forward ground speed for track keeping in excess wind - The maximum value of the minimum forward ground speed that may be commanded by the track keeping excess wind handling logic. Commanded in full at the normalized track error fraction of the track error boundary and reduced to zero on track. + + Idle throttle + This is the minimum throttle while on the ground For aircraft with internal combustion engine this parameter should be set above desired idle rpm. 0.0 - 10.0 - m/s - 1 - 0.5 - - - Enable automatic lower bound on the NPFG period - Avoids limit cycling from a too aggressively tuned period/damping combination. If set to false, also disables the upper bound NPFG_PERIOD_UB. + 0.4 + norm + 2 + 0.01 - - NPFG period - Period of the NPFG control law. - 1.0 - 100.0 - s - 1 - 0.1 - - - Period safety factor - Multiplied by period for conservative minimum period bounding (when period lower bounding is enabled). 1.0 bounds at marginal stability. - 1.0 - 10.0 - 1 - 0.1 - - - Roll time constant - Time constant of roll controller command / response, modeled as first order delay. Used to determine lower period bound. Setting zero disables automatic period bounding. - 0.00 - 2.00 - s + + Throttle limit during landing below throttle limit altitude + During the flare of the autonomous landing process, this value will be set as throttle limit when the aircraft altitude is below FW_LND_TLALT. + 0.0 + 1.0 + norm 2 - 0.05 + 0.01 - - NPFG switch distance multiplier - Multiplied by the track error boundary to determine when the aircraft switches to the next waypoint and/or path segment. Should be less than 1. - 0.1 + + Throttle limit max + This is the maximum throttle % that can be used by the controller. For overpowered aircraft, this should be reduced to a value that provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX. + 0.0 1.0 + norm 2 0.01 - - Enable track keeping excess wind handling logic - - - Enable automatic upper bound on the NPFG period - Adapts period to maintain track keeping in variable winds and path curvature. - - - Enable wind excess regulation - Disabling this parameter further disables all other airspeed incrementation options. - - - - - Path navigation roll slew rate limit - The maximum change in roll angle setpoint per second. - 0 - deg/s - 0 - 1 - - - RC stick configuration fixed-wing - Set RC/joystick configuration for fixed-wing manual position and altitude controlled flight. - 0 - 3 - - Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick) - Enable airspeed setpoint via sticks in altitude and position flight mode - + + Throttle limit min + This is the minimum throttle % that can be used by the controller. For electric aircraft this will normally be set to zero, but can be set to a small non-zero value if a folding prop is fitted to prevent the prop from folding and unfolding repeatedly in-flight or to provide some aerodynamic drag from a turning prop to improve the descent rate. For aircraft with internal combustion engine this parameter should be set for desired idle rpm. + 0.0 + 1.0 + norm + 2 + 0.01 - - Maximum roll angle - The maximum roll angle setpoint for setpoint for a height-rate or altitude controlled mode. - 35.0 - 65.0 - deg - 1 - 0.5 + + Throttle max slew rate + Maximum slew rate for the commanded throttle + 0.0 + 1.0 Minimum pitch during takeoff @@ -2956,1507 +3451,1303 @@ 0.5 - - - Acro body x max rate - This is the rate the controller is trying to achieve if the user applies full roll stick input in acro mode. - 10 - 720 - deg + + + Launch detection - - Enable yaw rate controller in Acro - If this parameter is set to 1, the yaw rate controller is enabled in Fixed-wing Acro mode. Otherwise the pilot commands directly the yaw actuator. It is disabled by default because an active yaw rate controller will fight against the natural turn coordination of the plane. + + Catapult accelerometer threshold + LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection. + 0 + m/s^2 + 1 + 0.5 - - Acro body pitch max rate setpoint - 10 - 720 - deg + + Motor delay + Delay between starting attitude control and powering up the throttle (giving throttle control to the controller) Before this timespan is up the throttle will be set to FW_THR_IDLE, set to 0 to deactivate + 0.0 + 10.0 + s + 1 + 0.5 - - Acro body yaw max rate setpoint - 10 - 720 + + Maximum pitch before the throttle is powered up (during motor delay phase) + This is an extra limit for the maximum pitch which is imposed in the phase before the throttle turns on. This allows to limit the maximum pitch angle during a bungee launch (make the launch less steep). + 0.0 + 45.0 deg + 1 + 0.5 - - Airspeed mode - On vehicles without airspeed sensor this parameter can be used to enable flying without an airspeed reading - - Use airspeed in controller - Do not use airspeed in controller - + + Catapult time threshold + LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection. + 0.0 + 5.0 + s + 2 + 0.05 - - Enable airspeed scaling - This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro) + + + + Maximum Airspeed (CAS) + If the CAS (calibrated airspeed) is above this value, the TECS controller will try to decrease airspeed more aggressively. + 0.5 + 40 + m/s + 1 + 0.5 - - Enable throttle scale by battery level - This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. + + Minimum Airspeed (CAS) + The minimal airspeed (calibrated airspeed) the user is able to command. Further, if the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. + 0.5 + 40 + m/s + 1 + 0.5 - - Pitch trim increment at maximum airspeed - This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX. - -0.5 - 0.5 - 2 - 0.01 + + Stall Airspeed (CAS) + The stall airspeed (calibrated airspeed) of the vehicle. It is used for airspeed sensor failure detection and for the control surface scaling airspeed limits. + 0.5 + 40 + m/s + 1 + 0.5 - - Pitch trim increment at minimum airspeed - This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN. - -0.5 - 0.5 - 2 - 0.01 + + Cruise Airspeed (CAS) + The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active, this is the default airspeed setpoint that the controller will try to achieve if no other airspeed setpoint sources are present (e.g. through non-centered RC sticks). + 0.5 + 40 + m/s + 1 + 0.5 - - Roll trim increment at maximum airspeed - This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX. - -0.5 - 0.5 - 2 - 0.01 + + Minimum groundspeed + The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint. + 0.0 + 40 + m/s + 1 + 0.5 - - Roll trim increment at minimum airspeed - This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN. - -0.5 - 0.5 + + Altitude error time constant + 2.0 2 - 0.01 + 0.5 - - Yaw trim increment at maximum airspeed - This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX. - -0.5 - 0.5 - 2 - 0.01 + + Maximum climb rate + This is the best climb rate that the aircraft can achieve with the throttle set to THR_MAX and the airspeed set to the default value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced. The setting of this parameter can be checked by commanding a positive altitude change of 100m in loiter, RTL or guided mode. If the throttle required to climb is close to THR_MAX and the aircraft is maintaining airspeed, then this parameter is set correctly. If the airspeed starts to reduce, then the parameter is set to high, and if the throttle demand required to climb and maintain speed is noticeably less than FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or FW_THR_MAX reduced. + 1.0 + 15.0 + m/s + 1 + 0.5 - - Yaw trim increment at minimum airspeed - This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN. - -0.5 - 0.5 + + Default target climbrate + The default rate at which the vehicle will climb in autonomous modes to achieve altitude setpoints. In manual modes this defines the maximum rate at which the altitude setpoint can be increased. + 0.5 + 15 + m/s 2 0.01 - - Flaps setting during landing - Sets a fraction of full flaps during landing. Also applies to flaperons if enabled in the mixer/allocation. + + Height rate feed forward 0.0 1.0 - norm 2 - 0.01 + 0.05 - - Flaps setting during take-off - Sets a fraction of full flaps during take-off. Also applies to flaperons if enabled in the mixer/allocation. + + Integrator gain pitch + This is the integrator gain on the pitch part of the control loop. Increasing this gain increases the speed at which speed and height offsets are trimmed out, but reduces damping and increases overshoot. Set this value to zero to completely disable all integrator action. 0.0 - 1.0 - norm + 2.0 2 - 0.01 + 0.05 - - Manual pitch scale - Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. + + Integrator gain throttle + This is the integrator gain on the throttle part of the control loop. Increasing this gain increases the speed at which speed and height offsets are trimmed out, but reduces damping and increases overshoot. Set this value to zero to completely disable all integrator action. 0.0 - norm + 2.0 2 - 0.01 + 0.05 - - Manual roll scale - Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. + + Pitch damping factor + This is the damping gain for the pitch demand loop. Increase to add damping to correct for oscillations in height. The default value of 0.0 will work well provided the pitch to servo controller has been tuned properly. 0.0 - 1.0 - norm + 2.0 2 - 0.01 + 0.1 - - Manual yaw scale - Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. + + Roll -> Throttle feedforward + Increasing this gain turn increases the amount of throttle that will be used to compensate for the additional drag created by turning. Ideally this should be set to approximately 10 x the extra sink rate in m/s created by a 45 degree bank turn. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns. Efficient high aspect-ratio aircraft (eg powered sailplanes) can use a lower value, whereas inefficient low aspect-ratio models (eg delta wings) can use a higher value. 0.0 - norm + 20.0 + 1 + 0.5 + + + Specific total energy balance rate feedforward gain + 0.5 + 3 2 0.01 - - Pitch rate derivative gain - Pitch rate differential gain. - 0.0 - 10 - %/rad/s - 3 - 0.005 + + Maximum descent rate + This sets the maximum descent rate that the controller will use. If this value is too large, the aircraft can over-speed on descent. This should be set to a value that can be achieved without exceeding the lower pitch angle limit and without over-speeding the aircraft. + 1.0 + 15.0 + m/s + 1 + 0.5 - - Pitch rate feed forward - Direct feed forward from rate setpoint to control surface output - 0.0 - 10.0 - %/rad/s - 2 - 0.05 - - - Pitch rate integrator gain - This gain defines how much control response will result out of a steady state error. It trims any constant error. - 0.0 - 10 - %/rad - 3 - 0.005 + + Minimum descent rate + This is the sink rate of the aircraft with the throttle set to THR_MIN and flown at the same airspeed as used to measure FW_T_CLMB_MAX. + 1.0 + 5.0 + m/s + 1 + 0.5 - - Pitch rate integrator limit - The portion of the integrator part in the control surface deflection is limited to this value - 0.0 - 1.0 + + Default target sinkrate + The default rate at which the vehicle will sink in autonomous modes to achieve altitude setpoints. In manual modes this defines the maximum rate at which the altitude setpoint can be decreased. + 0.5 + 15 + m/s 2 - 0.05 - - - Pitch rate proportional gain - 0.0 - 10 - %/rad/s - 3 - 0.005 - - - Roll control to yaw control feedforward gain - This gain can be used to counteract the "adverse yaw" effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator to counteract this effect. - 0.0 - 1 0.01 - - Roll rate derivative Gain - Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + + Speed <--> Altitude priority + This parameter adjusts the amount of weighting that the pitch control applies to speed vs height errors. Setting it to 0.0 will cause the pitch control to control height and ignore speed errors. This will normally improve height accuracy but give larger airspeed errors. Setting it to 2.0 will cause the pitch control loop to control speed and ignore height errors. This will normally reduce airspeed errors, but give larger height errors. The default value of 1.0 allows the pitch control to simultaneously control height and speed. Note to Glider Pilots - set this parameter to 2.0 (The glider will adjust its pitch angle to maintain airspeed, ignoring changes in height). 0.0 - 10 - %/rad/s - 3 - 0.005 + 2.0 + 1 + 1.0 - - Roll rate feed forward - Direct feed forward from rate setpoint to control surface output. Use this to obtain a tigher response of the controller without introducing noise amplification. - 0.0 + + Complementary filter "omega" parameter for speed + This is the cross-over frequency (in radians/second) of the complementary filter used to fuse longitudinal acceleration and airspeed to obtain an improved airspeed estimate. Increasing this frequency weights the solution more towards use of the airspeed sensor, whilst reducing it weights the solution more towards use of the accelerometer data. + 1.0 10.0 - %/rad/s - 2 - 0.05 + rad/s + 1 + 0.5 - - Roll rate integrator Gain - This gain defines how much control response will result out of a steady state error. It trims any constant error. + + Specific total energy rate first order filter time constant + This filter is applied to the specific total energy rate used for throttle damping. 0.0 - 10 - %/rad + 2 2 0.01 - - Roll integrator anti-windup - The portion of the integrator part in the control surface deflection is limited to this value. + + True airspeed rate first order filter time constant + This filter is applied to the true airspeed rate. 0.0 - 1.0 + 2 2 - 0.05 - - - Roll rate proportional Gain - 0.0 - 10 - %/rad/s - 3 - 0.005 - - - Spoiler input in manual flight - Chose source for manual setting of spoilers in manual flight modes. - - Disabled - Flaps channel - Aux1 - - - - Yaw rate derivative gain - Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - 0.0 - 10 - %/rad/s - 3 - 0.005 + 0.01 - - Yaw rate feed forward - Direct feed forward from rate setpoint to control surface output - 0.0 - 10.0 - %/rad/s + + True airspeed error time constant + 2.0 2 - 0.05 - - - Yaw rate integrator gain - This gain defines how much control response will result out of a steady state error. It trims any constant error. - 0.0 - 10 - %/rad - 1 0.5 - - Yaw rate integrator limit - The portion of the integrator part in the control surface deflection is limited to this value + + Throttle damping factor + This is the damping gain for the throttle demand loop. Increase to add damping to correct for oscillations in speed and height. 0.0 - 1.0 + 2.0 2 - 0.05 - - - Yaw rate proportional gain - 0.0 - 10 - %/rad/s - 3 - 0.005 - - - - - Maximum Airspeed (CAS) - The maximal airspeed (calibrated airspeed) the user is able to command. - 0.5 - m/s - 1 - 0.5 + 0.1 - - Minimum Airspeed (CAS) - The minimal airspeed (calibrated airspeed) the user is able to command. Further, if the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. Has to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL), with some margin between the stall speed and minimum airspeed. This value corresponds to the desired minimum speed with the default load factor (level flight, default weight), and is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE). - 0.5 - m/s + + Maximum vertical acceleration + This is the maximum vertical acceleration (in m/s/s) either up or down that the controller will use to correct speed or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) allows for reasonably aggressive pitch changes if required to recover from under-speed conditions. + 1.0 + 10.0 + m/s^2 1 0.5 - - Stall Airspeed (CAS) - The stall airspeed (calibrated airspeed) of the vehicle. It is used for airspeed sensor failure detection and for the control surface scaling airspeed limits. - 0.5 - m/s - 1 - 0.5 + + + + Enable checks on ESCs that report their arming state + If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle. - - Trim (Cruise) Airspeed - The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active, this is the default airspeed setpoint that the controller will try to achieve. - 0.5 - m/s - 1 - 0.5 + + Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS) + Enabled on either AUX5 or MAIN5 depending on board. External ATS is required by ASTM F3322-18. + true - - Minimum groundspeed - The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint. - 0.0 - 40 - m/s - 1 - 0.5 + + The PWM threshold from external automatic trigger system for engaging failsafe + External ATS is required by ASTM F3322-18. + us + 2 - - Maximum pitch angle - The maximum pitch angle setpoint setpoint for a height-rate or altitude controlled mode. - 0.0 - 60.0 + + FailureDetector Max Pitch + Maximum pitch angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check + 60 + 180 deg - 1 - 0.5 - - Minimum pitch angle - The minimum pitch angle setpoint for a height-rate or altitude controlled mode. - -60.0 - 0.0 + + Pitch failure trigger time + Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure. + 0.02 + 5 + s + 2 + + + FailureDetector Max Roll + Maximum roll angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check + 60 + 180 deg - 1 - 0.5 - - Throttle at max airspeed - Required throttle for level flight at maximum airspeed FW_AIRSPD_MAX (sea level, standard atmosphere) Set to 0 to disable mapping of airspeed to trim throttle. - 0 - 1 + + Roll failure trigger time + Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure. + 0.02 + 5 + s 2 - 0.01 - - Throttle at min airspeed - Required throttle for level flight at minimum airspeed FW_AIRSPD_MIN (sea level, standard atmosphere) Set to 0 to disable mapping of airspeed to trim throttle below FW_AIRSPD_TRIM. - 0 - 1 - 2 - 0.01 + + + + Distance to follow target from + The distance in meters to follow the target at + 1.0 + m - - Idle throttle - This is the minimum throttle while on the ground For aircraft with internal combustion engines, this parameter should be set above the desired idle rpm. For electric motors, idle should typically be set to zero. Note that in automatic modes, "landed" conditions will engage idle throttle. - 0.0 - 0.4 - norm - 2 - 0.01 + + Side to follow target from + The side to follow the target from (front right = 0, behind = 1, front = 2, front left = 3) + 0 + 3 - - Throttle limit max - This is the maximum throttle % that can be used by the controller. For overpowered aircraft, this should be reduced to a value that provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX. + + Dynamic filtering algorithm responsiveness to target movement + lower numbers increase the responsiveness to changing long lat but also ignore less noise 0.0 1.0 - norm 2 - 0.01 - - Throttle limit min - This is the minimum throttle % that can be used by the controller. For electric aircraft this will normally be set to zero, but can be set to a small non-zero value if a folding prop is fitted to prevent the prop from folding and unfolding repeatedly in-flight or to provide some aerodynamic drag from a turning prop to improve the descent rate. For aircraft with internal combustion engine this parameter should be set for desired idle rpm. - 0.0 - 1.0 - norm - 2 - 0.01 + + Minimum follow target altitude + The minimum height in meters relative to home for following a target + 8.0 + m - - Throttle max slew rate - Maximum slew rate for the commanded throttle - 0.0 - 1.0 - 2 - 0.01 + + + + Serial Configuration for Main GPS + Configure on which serial port to run Main GPS. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + - - Trim throttle - This is the throttle setting required to achieve FW_AIRSPD_TRIM during level flight. - 0.0 - 1.0 - norm - 2 - 0.01 + + GNSS Systems for Primary GPS (integer bitmask) + This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS + 0 + 31 + true + + GPS (with QZSS) + SBAS + Galileo + BeiDou + GLONASS + - - Takeoff Airspeed - The calibrated airspeed setpoint TECS will stabilize to during the takeoff climbout. If set <= 0.0, FW_AIRSPD_MIN will be set by default. - -1.0 - m/s - 1 - 0.1 + + Protocol for Main GPS + Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower. + 0 + 5 + true + + Auto detect + u-blox + MTK + Ashtech / Trimble + Emlid Reach + Femtomes + NMEA (generic) + - - Altitude error time constant - 2.0 - 2 - 0.5 + + Serial Configuration for Secondary GPS + Configure on which serial port to run Secondary GPS. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + - - Maximum climb rate - This is the maximum climb rate that the aircraft can achieve with the throttle set to THR_MAX and the airspeed set to the trim value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced. - 1.0 - 15.0 - m/s - 1 - 0.5 + + GNSS Systems for Secondary GPS (integer bitmask) + This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS + 0 + 31 + true + + GPS (with QZSS) + SBAS + Galileo + BeiDou + GLONASS + - - Default target climbrate - The default rate at which the vehicle will climb in autonomous modes to achieve altitude setpoints. In manual modes this defines the maximum rate at which the altitude setpoint can be increased. - 0.5 - 15 - m/s - 2 - 0.01 + + Protocol for Secondary GPS + Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower. + 0 + 5 + true + + Auto detect + u-blox + MTK + Ashtech / Trimble + Emlid Reach + Femtomes + NMEA (generic) + - - Height rate feed forward - 0.0 - 1.0 - 2 - 0.05 + + Log GPS communication data + If this is set to 1, all GPS communication data will be published via uORB, and written to the log file as gps_dump message. If this is set to 2, the main GPS is configured to output RTCM data, which is then logged as gps_dump and can be used for PPK. + 0 + 2 + + Disable + Full communication + RTCM output (PPK) + - - Integrator gain pitch - This is the integrator gain on the pitch part of the control loop. Increasing this gain increases the speed at which speed and height offsets are trimmed out, but reduces damping and increases overshoot. Set this value to zero to completely disable all integrator action. - 0.0 - 2.0 - 2 - 0.05 + + u-blox GPS dynamic platform model + u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment. + 0 + 9 + true + + stationary + automotive + airborne with <1g acceleration + airborne with <2g acceleration + airborne with <4g acceleration + - - Integrator gain throttle - This is the integrator gain on the throttle part of the control loop. Increasing this gain increases the speed at which speed and height offsets are trimmed out, but reduces damping and increases overshoot. Set this value to zero to completely disable all integrator action. - 0.0 - 2.0 - 2 - 0.05 + + u-blox GPS Mode + Select the u-blox configuration setup. Most setups will use the default, including RTK and dual GPS without heading. The Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output heading information, whereas the secondary will act as moving base, sending RTCM on UART2 to the rover GPS. RTK is still possible with this setup. + 0 + 1 + true + + Default + Heading + - - Pitch damping factor - This is the damping gain for the pitch demand loop. Increase to add damping to correct for oscillations in height. The default value of 0.0 will work well provided the pitch to servo controller has been tuned properly. - 0.0 - 2.0 - 2 - 0.1 + + Heading/Yaw offset for dual antenna GPS + Heading offset angle for dual antenna GPS setups that support heading estimation. (currently only for the Trimble MB-Two). Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the first antenna is in front. The offset angle increases clockwise. Set this to 90 if the first antenna is placed on the right side and the second on the left side of the vehicle. + 0 + 360 + deg + 0 + true - - Roll -> Throttle feedforward - Increasing this gain turn increases the amount of throttle that will be used to compensate for the additional drag created by turning. Ideally this should be set to approximately 10 x the extra sink rate in m/s created by a 45 degree bank turn. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns. Efficient high aspect-ratio aircraft (eg powered sailplanes) can use a lower value, whereas inefficient low aspect-ratio models (eg delta wings) can use a higher value. + + + + Loiter time + The time in seconds the system should do open loop loiter and wait for GPS recovery before it goes into flight termination. Set to 0 to disable. 0.0 - 20.0 - 1 - 0.5 - - - Specific total energy balance rate feedforward gain - 0.5 - 3 - 2 - 0.01 + 3600.0 + s + 0 + 1 - - Maximum descent rate - This sets the maximum descent rate that the controller will use. If this value is too large, the aircraft can over-speed on descent. This should be set to a value that can be achieved without exceeding the lower pitch angle limit and without over-speeding the aircraft. - 1.0 - 15.0 - m/s + + Fixed pitch angle + Pitch in degrees during the open loop loiter + -30.0 + 30.0 + deg 1 0.5 - - Minimum descent rate - This is the sink rate of the aircraft with the throttle set to THR_MIN and flown at the same airspeed as used to measure FW_T_CLMB_MAX. - 1.0 - 5.0 - m/s + + Fixed bank angle + Roll in degrees during the loiter + 0.0 + 30.0 + deg 1 0.5 - - Default target sinkrate - The default rate at which the vehicle will sink in autonomous modes to achieve altitude setpoints. In manual modes this defines the maximum rate at which the altitude setpoint can be decreased. - 0.5 - 15 - m/s - 2 - 0.01 - - - Speed <--> Altitude priority - This parameter adjusts the amount of weighting that the pitch control applies to speed vs height errors. Setting it to 0.0 will cause the pitch control to control height and ignore speed errors. This will normally improve height accuracy but give larger airspeed errors. Setting it to 2.0 will cause the pitch control loop to control speed and ignore height errors. This will normally reduce airspeed errors, but give larger height errors. The default value of 1.0 allows the pitch control to simultaneously control height and speed. Set to 2 for gliders. + + Thrust + Thrust value which is set during the open loop loiter 0.0 - 2.0 - 1 - 1.0 - - - Airspeed rate measurement standard deviation for airspeed filter - This is the measurement standard deviation for the airspeed rate used in the airspeed filter in TECS. - 0.01 - 10.0 - m/s^2 - 2 - 0.1 - - - Process noise standard deviation for the airspeed rate in the airspeed filter - This is the process noise standard deviation in the airspeed filter filter defining the noise in the airspeed rate for the constant airspeed rate model. This is used to define how much the airspeed and the airspeed rate are filtered. The smaller the value the more the measurements are smoothed with the drawback for delays. - 0.01 - 10.0 - m/s^2 + 1.0 + norm 2 - 0.1 + 0.05 - - Airspeed measurement standard deviation for airspeed filter - This is the measurement standard deviation for the airspeed used in the airspeed filter in TECS. - 0.01 - 10.0 - m/s - 2 - 0.1 + + + + Geofence violation action + Note: Setting this value to 4 enables flight termination, which will kill the vehicle on violation of the fence. Due to the inherent danger of this, this function is disabled using a software circuit breaker, which needs to be reset to 0 to really shut down the system. + 0 + 5 + + None + Warning + Hold mode + Return mode + Terminate + Land mode + - - Specific total energy rate first order filter time constant - This filter is applied to the specific total energy rate used for throttle damping. - 0.0 - 2 - 2 - 0.01 + + Geofence altitude mode + Select which altitude (AMSL) source should be used for geofence calculations. + 0 + 1 + + Autopilot estimator global position altitude (GPS) + Raw barometer altitude (assuming standard atmospheric pressure) + - - True airspeed error time constant - 2.0 - 2 - 0.5 + + Geofence counter limit + Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered + -1 + 10 + 1 - - Throttle damping factor - This is the damping gain for the throttle demand loop. Increase to add damping to correct for oscillations in speed and height. - 0.0 - 2.0 - 2 - 0.1 + + Max horizontal distance in meters + Maximum horizontal distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. + 0 + 10000 + m + 1 - - Maximum vertical acceleration - This is the maximum vertical acceleration (in m/s/s) either up or down that the controller will use to correct speed or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) allows for reasonably aggressive pitch changes if required to recover from under-speed conditions. - 1.0 - 10.0 - m/s^2 - 1 - 0.5 + + Max vertical distance in meters + Maximum vertical distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. + 0 + 10000 + m + 1 - - Wind-based airspeed scaling factor - Multiplying this factor with the current absolute wind estimate gives the airspeed offset added to the minimum airspeed setpoint limit. This helps to make the system more robust against disturbances (turbulence) in high wind. Only applies to AUTO flight mode. airspeed_min_adjusted = FW_AIRSPD_MIN + FW_WIND_ARSP_SC * wind.length() + + Geofence source + Select which position source should be used. Selecting GPS instead of global position makes sure that there is no dependence on the position estimator 0 = global position, 1 = GPS 0 - 2 - 0.01 + 1 + + GPOS + GPS + - - - Enable Actuator Failure check - If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle level is being consumed. Otherwise this indicates an motor failure. - true - - - Motor Failure Current/Throttle Threshold - Motor failure triggers only below this current value - 0.0 - 50.0 - A/% - 2 - 1 + + + Gate size for acceleration fusion + Sets the number of standard deviations used by the innovation consistency test. + 1.0 + 10.0 + SD + 1 - - Motor Failure Throttle Threshold - Motor failure triggers only above this throttle value. + + 1-sigma initial hover thrust uncertainty + Sets the number of standard deviations used by the innovation consistency test. 0.0 1.0 - norm - 2 - 0.01 - - - Motor Failure Time Threshold - Motor failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time. - 10 - 10000 - ms - 100 + normalized_thrust + 3 - - Enable checks on ESCs that report their arming state - If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle. + + Hover thrust process noise + Reduce to make the hover thrust estimate more stable, increase if the real hover thrust is expected to change quickly over time. + 0.0001 + 1.0 + normalized_thrust/s + 4 - - Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS) - Enabled on either AUX5 or MAIN5 depending on board. External ATS is required by ASTM F3322-18. + + + + Serial Configuration for Iridium (with MAVLink) + Configure on which serial port to run Iridium (with MAVLink). true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + - - The PWM threshold from external automatic trigger system for engaging failsafe - External ATS is required by ASTM F3322-18. - us - 2 - - - FailureDetector Max Pitch - Maximum pitch angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check + + Satellite radio read interval. Only required to be nonzero if data is not sent using a ring call 0 - 180 - deg - - - Pitch failure trigger time - Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure. - 0.02 - 5 + 5000 s - 2 - - FailureDetector Max Roll - Maximum roll angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check + + Iridium SBD session timeout 0 - 180 - deg - - - Roll failure trigger time - Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure. - 0.02 - 5 + 300 s - 2 - - Imbalanced propeller check threshold - Value at which the imbalanced propeller metric (based on horizontal and vertical acceleration variance) triggers a failure Setting this value to 0 disables the feature. + + Time the Iridium driver will wait for additional mavlink messages to combine them into one SBD message + Value 0 turns the functionality off 0 - 1000 - 1 + 500 + ms - - - Maximum radius of orbit - 1.0 - 10000.0 - m + + + Airspeed max + Maximum airspeed allowed in the landed state + 4 + 20 + m/s 1 - 0.5 - - - - Altitude control mode - Maintain altitude or track target's altitude. When maintaining the altitude, the drone can crash into terrain when the target moves uphill. When tracking the target's altitude, the follow altitude FLW_TGT_HT should be high enough to prevent terrain collisions due to GPS inaccuracies of the target. - - 2D Tracking: Maintain constant altitude relative to home and track XY position only - 2D + Terrain: Maintain constant altitude relative to terrain below and track XY position - 3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless) - + + Fixedwing max horizontal velocity + Maximum horizontal velocity allowed in the landed state + 0.5 + 10 + m/s + 1 - - Distance to follow target from - The distance in meters to follow the target at - 1.0 - m + + Fixedwing max climb rate + Maximum vertical velocity allowed in the landed state + 0.1 + 20 + m/s + 1 - - Follow Angle setting in degrees - Angle to follow the target from. 0.0 Equals straight in front of the target's course (direction of motion) and the angle increases in clockwise direction, meaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees Note: When the user force sets the angle out of the min/max range, it will be wrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range. - -180.0 - 180.0 + + Fixedwing max horizontal acceleration + Maximum horizontal (x,y body axes) acceleration allowed in the landed state + 2 + 15 + m/s^2 + 1 - - Follow target height - Following height above the target - 8.0 + + Ground effect altitude for multicopters + The height above ground below which ground effect creates barometric altitude errors. A negative value indicates no ground effect. + -1 m + 2 - - Maximum tangential velocity setting for generating the follow orbit trajectory - This is the maximum tangential velocity the drone will circle around the target whenever an orbit angle setpoint changes. Higher value means more aggressive follow behavior. - 0.0 - 20.0 + + Maximum altitude for multicopters + The system will obey this limit as a hard altitude limit. This setting will be consolidated with the GF_MAX_VER_DIST parameter. A negative value indicates no altitude limitation. + -1 + 10000 + m + 2 + + + Multicopter max rotation + Maximum allowed angular velocity around each axis allowed in the landed state. + deg/s 1 - - Responsiveness to target movement in Target Estimator - lower values increase the responsiveness to changing position, but also ignore less noise - 0.0 - 1.0 - 2 + + Multicopter land detection trigger time + Total time it takes to go through all three land detection stages: ground contact, maybe landed, landed when all necessary conditions are constantly met. + 0.1 + 10.0 + s + 1 - - - - GNSS Systems for Primary GPS (integer bitmask) - This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS + + Multicopter max horizontal velocity + Maximum horizontal velocity allowed in the landed state + m/s + 1 + + + Multicopter max climb rate + Maximum vertical velocity allowed in the landed state + m/s + 1 + + + Total flight time in microseconds + Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. 0 - 31 - true - - GPS (with QZSS) - SBAS - Galileo - BeiDou - GLONASS - - - Protocol for Main GPS - Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower. + + Total flight time in microseconds + Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. 0 - 7 - true - - Auto detect - u-blox - MTK - Ashtech / Trimble - Emlid Reach - Femtomes - NMEA (generic) - Septentrio (SBF) - - - GNSS Systems for Secondary GPS (integer bitmask) - This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS - 0 - 31 - true - - GPS (with QZSS) - SBAS - Galileo - BeiDou - GLONASS - + + + + Acceleration uncertainty + Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection + 0.01 + (m/s^2)^2 + 2 - - Protocol for Secondary GPS - Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower. - 0 - 6 - true - - Auto detect - u-blox - MTK - Ashtech / Trimble - Emlid Reach - Femtomes - NMEA (generic) - + + Landing target measurement uncertainty + Variance of the landing target measurement from the driver. Higher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements. + tan(rad)^2 + 4 - - Log GPS communication data - If this is set to 1, all GPS communication data will be published via uORB, and written to the log file as gps_dump message. If this is set to 2, the main GPS is configured to output RTCM data, which is then logged as gps_dump and can be used for PPK. + + Landing target mode + Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation. 0 - 2 + 1 - Disable - Full communication - RTCM output (PPK) + Moving + Stationary - - Pitch offset for dual antenna GPS - Vertical offsets can be compensated for by adjusting the Pitch offset (Septentrio). Note that this can be interpreted as the "roll" angle in case the antennas are aligned along the perpendicular axis. This occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame. Since pitch is defined as the right-handed rotation about the vehicle Y axis, a situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch. - -90 - 90 - deg + + Initial landing target position uncertainty + Initial variance of the relative landing target position in x and y direction + 0.001 + m^2 3 - true - - Enable sat info (if available) - Enable publication of satellite info (ORB_ID(satellite_info)) if possible. Not available on MTK. - true + + Scale factor for sensor measurements in sensor x axis + Landing target x measurements are scaled by this factor before being used + 0.01 + 3 - - u-blox F9P UART2 Baudrate - Select a baudrate for the F9P's UART2 port. In GPS_UBX_MODE 1, 2, and 3, the F9P's UART2 port is configured to send/receive RTCM corrections. Set this to 57600 if you want to attach a telemetry radio on UART2. - 0 - B/s - true + + Scale factor for sensor measurements in sensor y axis + Landing target y measurements are scaled by this factor before being used + 0.01 + 3 - - u-blox protocol configuration for interfaces - 0 - 32 - true - - Enable I2C input protocol UBX - Enable I2C input protocol NMEA - Enable I2C input protocol RTCM3X - Enable I2C output protocol UBX - Enable I2C output protocol NMEA - Enable I2C output protocol RTCM3X - + + Initial landing target velocity uncertainty + Initial variance of the relative landing target velocity in x and y directions + 0.001 + (m/s)^2 + 3 - - u-blox GPS dynamic platform model - u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment. - 0 - 9 - true - - stationary - automotive - airborne with <1g acceleration - airborne with <2g acceleration - airborne with <4g acceleration - + + + + Accelerometer xy noise density + Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error. + 0.00001 + 2 + m/s^2/sqrt(Hz) + 4 - - u-blox GPS Mode - Select the u-blox configuration setup. Most setups will use the default, including RTK and dual GPS without heading. If rover has RTCM corrections from a static base (or other static correction source) coming in on UART2, then select Mode 5. The Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output heading information, whereas the secondary will act as moving base. Modes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the F9P units are connected to each other. Modes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required. RTK is still possible with this setup. - 0 - 1 - true - - Default - Heading (Rover With Moving Base UART1 Connected To Autopilot, UART2 Connected To Moving Base) - Moving Base (UART1 Connected To Autopilot, UART2 Connected To Rover) - Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600) - Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600) - Rover with Static Base on UART2 (similar to Default, except coming in on UART2) - + + Accelerometer z noise density + Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) + 0.00001 + 2 + m/s^2/sqrt(Hz) + 4 - - Heading/Yaw offset for dual antenna GPS - Heading offset angle for dual antenna GPS setups that support heading estimation. Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the rover (or Unicore primary) antenna is in front. The offset angle increases clockwise. Set this to 90 if the rover (or Unicore primary) antenna is placed on the right side of the vehicle and the moving base antenna is on the left side. (Note: the Unicore primary antenna is the one connected on the right as seen from the top). - 0 - 360 - deg - 3 - true + + Barometric presssure altitude z standard deviation + 0.01 + 100 + m + 2 - - PPS Capture Enable - Enables the PPS capture module. This switches mode of FMU channel 7 to be the PPS input channel. - true + + Max EPH allowed for GPS initialization + 1.0 + 5.0 + m + 3 - - - - Geofence violation action - Note: Setting this value to 4 enables flight termination, which will kill the vehicle on violation of the fence. - 0 - 5 - - None - Warning - Hold mode - Return mode - Terminate - Land mode - + + Max EPV allowed for GPS initialization + 1.0 + 5.0 + m + 3 - - Geofence altitude mode - Select which altitude (AMSL) source should be used for geofence calculations. + + Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow) + By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable 0 1 - - Autopilot estimator global position altitude (GPS) - Raw barometer altitude (assuming standard atmospheric pressure) - - - - Geofence counter limit - Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered - -1 - 10 - 1 - - Max horizontal distance in meters - Maximum horizontal distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. + + Flow gyro high pass filter cut off frequency 0 - 10000 - m - 1 + 2 + Hz + 3 - - Max vertical distance in meters - Maximum vertical distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. - 0 - 10000 + + Optical flow z offset from center + -1 + 1 m - 1 - - - [EXPERIMENTAL] Use Pre-emptive geofence triggering - WARNING: This experimental feature may cause flyaways. Use at your own risk. Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory would result in a breach happening before the vehicle can make evasive maneuvers. The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing). + 3 - - Geofence source - Select which position source should be used. Selecting GPS instead of global position makes sure that there is no dependence on the position estimator 0 = global position, 1 = GPS + + Optical flow minimum quality threshold 0 - 1 - - GPOS - GPS - + 255 + 0 - - - - Gate size for acceleration fusion - Sets the number of standard deviations used by the innovation consistency test. - 1.0 + + Optical flow rotation (roll/pitch) noise gain + 0.1 10.0 - SD - 1 + m/s/rad + 3 - - 1-sigma initial hover thrust uncertainty - Sets the number of standard deviations used by the innovation consistency test. + + Optical flow angular velocity noise gain 0.0 - 1.0 - normalized_thrust + 10.0 + m/rad 3 - - Hover thrust process noise - Reduce to make the hover thrust estimate more stable, increase if the real hover thrust is expected to change quickly over time. - 0.0001 - 1.0 - normalized_thrust/s - 4 + + Optical flow scale + 0.1 + 10.0 + m + 3 - - Max deviation from MPC_THR_HOVER - Defines the range of the hover thrust estimate around MPC_THR_HOVER. A value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7]. Set to a large value if the vehicle operates in varying physical conditions that affect the required hover thrust strongly (e.g. differently sized payloads). - 0.01 - 0.4 - normalized_thrust - 2 - - - Horizontal velocity threshold for sensitivity reduction - Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles with large lifting surfaces. - 1.0 - 20.0 - m/s - 1 - - - Vertical velocity threshold for sensitivity reduction - Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles affected by air drag when climbing or descending. - 1.0 - 10.0 - m/s - 1 - - - - - Satellite radio read interval. Only required to be nonzero if data is not sent using a ring call - 0 - 5000 - s - - - Iridium SBD session timeout + + Integer bitmask controlling data fusion + Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector) 0 - 300 - s + 255 + + fuse GPS, requires GPS for alt. init + fuse optical flow + fuse vision position + fuse landing target + fuse land detector + pub agl as lpos down + flow gyro compensation + fuse baro + - - Time the Iridium driver will wait for additional mavlink messages to combine them into one SBD message - Value 0 turns the functionality off + + GPS delay compensaton 0 - 500 - ms - - - - - Fixed-wing land detector: Max airspeed - Maximum airspeed allowed in the landed state - 2 - 20 - m/s - 1 - - - Fixed-wing land detection trigger time - Time the land conditions (speeds and acceleration) have to be satisfied to detect a landing. - 0.1 + 0.4 s - 1 - true + 2 - - Fixed-wing land detector: Max horizontal velocity threshold - Maximum horizontal velocity allowed in the landed state. A factor of 0.7 is applied in case of airspeed-less flying (either because no sensor is present or sensor data got invalid in flight). - 0.5 - 10 + + GPS xy velocity standard deviation + EPV used if greater than this value. + 0.01 + 2 m/s - 1 + 3 - - Fixed-wing land detector: Max vertiacal velocity threshold - Maximum vertical velocity allowed in the landed state. - 0.1 - 20 + + GPS z velocity standard deviation + 0.01 + 2 m/s - 1 - - - Fixed-wing land detector: Max horizontal acceleration - Maximum horizontal (x,y body axes) acceleration allowed in the landed state - 2 - 15 - m/s^2 - 1 + 3 - - Ground effect altitude for multicopters - The height above ground below which ground effect creates barometric altitude errors. A negative value indicates no ground effect. - -1 + + Minimum GPS xy standard deviation, uses reported EPH if greater + 0.01 + 5 m 2 - - Maximum altitude for multicopters - The system will obey this limit as a hard altitude limit. This setting will be consolidated with the GF_MAX_VER_DIST parameter. A negative value indicates no altitude limitation. - -1 - 10000 + + Minimum GPS z standard deviation, uses reported EPV if greater + 0.01 + 200 m 2 - - Multicopter max rotation - Maximum allowed angular velocity around each axis allowed in the landed state. - deg/s - 1 - - - Multicopter land detection trigger time - Total time it takes to go through all three land detection stages: ground contact, maybe landed, landed when all necessary conditions are constantly met. - 0.1 + + Land detector xy velocity standard deviation + 0.01 10.0 - s - 1 - - - Multicopter max horizontal velocity - Maximum horizontal velocity allowed in the landed state m/s - 1 + 3 - - Multicopter vertical velocity threshold - Vertical velocity threshold to detect landing. Has to be set lower than the expected minimal speed for landing, which is either MPC_LAND_SPEED or MPC_LAND_CRWL. This is enforced by an automatic check. - 0 - m/s - 2 + + Land detector z standard deviation + 0.001 + 10.0 + m + 3 - - Total flight time in microseconds - Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. - 0 + + Local origin latitude for nav w/o GPS + -90 + 90 + deg + 8 - - Total flight time in microseconds - Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. - 0 + + Lidar z offset from center of vehicle +down + -1 + 1 + m + 3 - - - - Acceleration uncertainty - Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection + + Lidar z standard deviation 0.01 - (m/s^2)^2 + 1 + m + 3 + + + Local origin longitude for nav w/o GPS + -180 + 180 + deg + 8 + + + Minimum landing target standard covariance, uses reported covariance if greater + 0.0 + 10 + m^2 2 - - Landing target measurement uncertainty - Variance of the landing target measurement from the driver. Higher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements. - tan(rad)^2 - 4 + + Accel bias propagation noise density + 0 + 1 + m/s^3/sqrt(Hz) + 8 - - Landing target mode - Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation. + + Position propagation noise density + Increase to trust measurements more. Decrease to trust model more. 0 1 - - Moving - Stationary - + m/s/sqrt(Hz) + 8 - - Initial landing target position uncertainty - Initial variance of the relative landing target position in x and y direction - 0.001 - m^2 + + Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001) + 0 + 1 + m/s/sqrt(Hz) 3 - - Scale factor for sensor measurements in sensor x axis - Landing target x measurements are scaled by this factor before being used - 0.01 - 3 + + Velocity propagation noise density + Increase to trust measurements more. Decrease to trust model more. + 0 + 1 + m/s^2/sqrt(Hz) + 8 - - Scale factor for sensor measurements in sensor y axis - Landing target y measurements are scaled by this factor before being used - 0.01 + + Sonar z offset from center of vehicle +down + -1 + 1 + m 3 - - X Position of IRLOCK in body frame (forward) + + Sonar z standard deviation + 0.01 + 1 m 3 - true - - Y Position of IRLOCK in body frame (right) - m + + Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg) + Used to calculate increased terrain random walk nosie due to movement. + 0 + 100 + % 3 - true - - Z Position of IRLOCK in body frame (downward) + + Vicon position standard deviation + 0.0001 + 1 m - 3 - true + 4 - - Rotation of IRLOCK sensor relative to airframe - Default orientation of Yaw 90° - -1 - 40 - true - - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - + + Vision delay compensation + Set to zero to enable automatic compensation from measurement timestamps + 0 + 0.1 + s + 2 - - Initial landing target velocity uncertainty - Initial variance of the relative landing target velocity in x and y directions - 0.001 - (m/s)^2 + + Vision xy standard deviation + 0.01 + 1 + m 3 - - - - Accelerometer xy noise density - Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error. - 0.00001 - 2 - m/s^2/sqrt(Hz) - 4 - - - Accelerometer z noise density - Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) - 0.00001 - 2 - m/s^2/sqrt(Hz) - 4 - - - Barometric presssure altitude z standard deviation + + Vision z standard deviation 0.01 100 m - 2 - - - Max EPH allowed for GPS initialization - 1.0 - 5.0 - m 3 - - Max EPV allowed for GPS initialization - 1.0 - 5.0 - m + + Required velocity xy standard deviation to publish position + 0.01 + 1.0 + m/s 3 - - Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow) - By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable - 0 - 1 - - - Flow gyro high pass filter cut off frequency - 0 - 2 + + Cut frequency for state publication + 5 + 1000 Hz - 3 + 0 - - Optical flow z offset from center - -1 - 1 + + Required z standard deviation to publish altitude/ terrain + 0.3 + 5.0 m - 3 + 1 - - Optical flow minimum quality threshold + + + + Broadcast heartbeats on local network for MAVLink instance 0 + This allows a ground control station to automatically find the drone on the local network. + + Never broadcast + Always broadcast + Only multicast + + + + Serial Configuration for MAVLink (instance 0) + Configure on which serial port to run MAVLink. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + Ethernet + + + + Enable MAVLink Message forwarding for instance 0 + If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). + True + + + MAVLink Mode for instance 0 + The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates. + True + + Normal + Custom + Onboard + OSD + Magic + Config + Minimal + External Vision + Gimbal + Onboard Low Bandwidth + + + + Enable software throttling of mavlink on instance 0 + If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS. + True + + + Maximum MAVLink sending rate for instance 0 + Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links). 0 - 255 + B/s + True - - Optical flow rotation (roll/pitch) noise gain - 0.1 - 10.0 - m/s/rad - 3 + + MAVLink Remote Port for instance 0 + If ethernet enabled and selected as configuration for MAVLink instance 0, selected remote port will be set and used in MAVLink instance 0. + True - - Optical flow angular velocity noise gain - 0.0 - 10.0 - m/rad - 3 + + MAVLink Network Port for instance 0 + If ethernet enabled and selected as configuration for MAVLink instance 0, selected udp port will be set and used in MAVLink instance 0. + True - - Optical flow scale - 0.1 - 10.0 - m - 3 + + Broadcast heartbeats on local network for MAVLink instance 1 + This allows a ground control station to automatically find the drone on the local network. + + Never broadcast + Always broadcast + Only multicast + - - Integer bitmask controlling data fusion - Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector) + + Serial Configuration for MAVLink (instance 1) + Configure on which serial port to run MAVLink. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + Ethernet + + + + Enable MAVLink Message forwarding for instance 1 + If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). + True + + + MAVLink Mode for instance 1 + The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates. + True + + Normal + Custom + Onboard + OSD + Magic + Config + Minimal + External Vision + Gimbal + Onboard Low Bandwidth + + + + Enable software throttling of mavlink on instance 1 + If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS. + True + + + Maximum MAVLink sending rate for instance 1 + Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links). 0 - 255 - - fuse GPS, requires GPS for alt. init - fuse optical flow - fuse vision position - fuse landing target - fuse land detector - pub agl as lpos down - flow gyro compensation - fuse baro - + B/s + True - - GPS delay compensaton - 0 - 0.4 - s - 2 + + MAVLink Remote Port for instance 1 + If ethernet enabled and selected as configuration for MAVLink instance 1, selected remote port will be set and used in MAVLink instance 1. + True - - GPS xy velocity standard deviation - EPV used if greater than this value. - 0.01 - 2 - m/s - 3 + + MAVLink Network Port for instance 1 + If ethernet enabled and selected as configuration for MAVLink instance 1, selected udp port will be set and used in MAVLink instance 1. + True - - GPS z velocity standard deviation - 0.01 - 2 - m/s - 3 + + Broadcast heartbeats on local network for MAVLink instance 2 + This allows a ground control station to automatically find the drone on the local network. + + Never broadcast + Always broadcast + Only multicast + - - Minimum GPS xy standard deviation, uses reported EPH if greater - 0.01 - 5 - m - 2 + + Serial Configuration for MAVLink (instance 2) + Configure on which serial port to run MAVLink. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + Ethernet + + + + Enable MAVLink Message forwarding for instance 2 + If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). + True + + + MAVLink Mode for instance 2 + The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates. + True + + Normal + Custom + Onboard + OSD + Magic + Config + Minimal + External Vision + Gimbal + Onboard Low Bandwidth + + + + Enable software throttling of mavlink on instance 2 + If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS. + True + + + Maximum MAVLink sending rate for instance 2 + Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links). + 0 + B/s + True - - Minimum GPS z standard deviation, uses reported EPV if greater - 0.01 - 200 - m - 2 + + MAVLink Remote Port for instance 2 + If ethernet enabled and selected as configuration for MAVLink instance 2, selected remote port will be set and used in MAVLink instance 2. + True - - Land detector xy velocity standard deviation - 0.01 - 10.0 - m/s - 3 + + MAVLink Network Port for instance 2 + If ethernet enabled and selected as configuration for MAVLink instance 2, selected udp port will be set and used in MAVLink instance 2. + True - - Land detector z standard deviation - 0.001 - 10.0 - m - 3 + + MAVLink component ID + 1 + 250 + true - - Local origin latitude for nav w/o GPS - -90 - 90 - deg - 8 + + Forward external setpoint messages + If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode - - Lidar z offset from center of vehicle +down - -1 - 1 - m - 3 + + Parameter hash check + Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously. - - Lidar z standard deviation - 0.01 - 1 - m - 3 + + Hearbeat message forwarding + The 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. - - Local origin longitude for nav w/o GPS - -180 - 180 - deg - 8 + + 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. - - Minimum landing target standard covariance, uses reported covariance if greater - 0.0 - 10 - m^2 - 2 + + MAVLink protocol version + + Default to 1, switch to 2 if GCS sends version 2 + Always use version 1 + Always use version 2 + - - Accel bias propagation noise density - 0 - 1 - m/s^3/sqrt(Hz) - 8 - - - Position propagation noise density - Increase to trust measurements more. Decrease to trust model more. - 0 - 1 - m/s/sqrt(Hz) - 8 - - - Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001) - 0 - 1 - m/s/sqrt(Hz) - 3 - - - Velocity propagation noise density - Increase to trust measurements more. Decrease to trust model more. - 0 - 1 - m/s^2/sqrt(Hz) - 8 - - - Sonar z offset from center of vehicle +down - -1 - 1 - m - 3 - - - Sonar z standard deviation - 0.01 - 1 - m - 3 - - - Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg) - Used to calculate increased terrain random walk nosie due to movement. - 0 - 100 - % - 3 - - - Vicon position standard deviation - 0.0001 - 1 - m - 4 - - - Vision delay compensation - Set to zero to enable automatic compensation from measurement timestamps - 0 - 0.1 - s - 2 - - - Vision xy standard deviation - 0.01 - 1 - m - 3 - - - Vision z standard deviation - 0.01 - 100 - m - 3 - - - Required velocity xy standard deviation to publish position - 0.01 - 1.0 - m/s - 3 - - - Cut frequency for state publication - 5 - 1000 - Hz - 0 - - - Required z standard deviation to publish altitude/ terrain - 0.3 - 5.0 - m - 1 - - - - - MAVLink component ID - 1 - 250 - true - - - Forward external setpoint messages - If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode - - - Parameter hash check - Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously. - - - Heartbeat message forwarding - The mavlink heartbeat 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. - - - MAVLink protocol version - - Default to 1, switch to 2 if GCS sends version 2 - Always use version 1 - Always use version 2 - - - - Timeout in seconds for the RADIO_STATUS reports coming in - If the connected radio stops reporting RADIO_STATUS for a certain time, a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow control is reset. - 1 - 250 - s + + Timeout in seconds for the RADIO_STATUS reports coming in + If the connected radio stops reporting RADIO_STATUS for a certain time, a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow control is reset. + 1 + 250 + s MAVLink SiK Radio ID @@ -4470,29 +4761,39 @@ 250 true - + MAVLink airframe type - 0 - 22 + 1 + 27 Generic micro air vehicle Fixed wing aircraft Quadrotor Coaxial helicopter Normal helicopter with tail rotor + Ground installation + Operator control unit / ground control station Airship, controlled Free balloon, uncontrolled + Rocket Ground rover Surface vessel, boat, ship Submarine Hexarotor Octorotor Tricopter - VTOL Two-rotor Tailsitter - VTOL Quad-rotor Tailsitter - VTOL Tiltrotor - VTOL Standard (separate fixed rotors for hover and cruise flight) - VTOL Tailsitter + Flapping wing + Kite + Onboard companion controller + Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. + Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. + Tiltrotor VTOL + VTOL reserved 2 + VTOL reserved 3 + VTOL reserved 4 + VTOL reserved 5 + Onboard gimbal + Onboard ADSB peripheral @@ -4500,172 +4801,33 @@ If set to 1 incoming HIL GPS messages are parsed. - - - UART ESC baud rate - Default rate is 250Kbps, which is used in off-the-shelf MoadalAI ESC products. - bit/s - - - UART ESC configuration - Selects what type of UART ESC, if any, is being used. - 0 - 1 - true - - - Disabled - - VOXL ESC - - - - UART ESC Mode - Selects what type of mode is enabled, if any - 0 - 2 - true - - - None - - Turtle Mode enabled via AUX1 - - Turtle Mode enabled via AUX2 - - UART Passthrough Mode - - - - UART ESC RPM Max - Maximum RPM for ESC - rpm - - - UART ESC RPM Min - Minimum RPM for ESC - rpm - - - UART ESC ID 1 Spin Direction Flag - - - Default - - Reverse - - - - UART ESC ID 2 Spin Direction Flag - - - Default - - Reverse - - - - UART ESC ID 3 Spin Direction Flag - - - Default - - Reverse - - - - UART ESC ID 4 Spin Direction Flag - - - Default - - Reverse - - - - UART ESC Turtle Mode Cosphi - 0.000 - 1.000 - 10 - 0.001 - - - UART ESC Turtle Mode Crash Flip Motor Deadband - 0 - 100 - 10 - 1 - - - UART ESC Turtle Mode Crash Flip Motor expo - 0 - 100 - 10 - 1 - - - UART ESC Turtle Mode Crash Flip Motor STICK_MINF - 0.0 - 100.0 - 10 - 1.0 - - - UART ESC Turtle Mode Crash Flip Motor Percent - 1 - 100 - 10 - 1 - - - UART ESC verbose logging - 0 - 1 - true - - - Disabled - - Enabled - - - - - - Enable online mag bias calibration - This enables continuous calibration of the magnetometers before takeoff using gyro data. - true - - - Mag bias estimator learning gain - Increase to make the estimator more responsive Decrease to make the estimator more robust to noise - 0.1 - 100 - 1 - 0.1 - - - - - Enable arm/disarm stick gesture - This determines if moving the left stick to the lower right arms and to the lower left disarms the vehicle. - - - - GPS failure loiter time - The time in seconds the system should do open loop loiter and wait for GPS recovery before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0. + + Maximal horizontal distance from home to first waypoint + Failsafe check to prevent running mission stored from previous flight at a new takeoff location. Set a value of zero or less to disable. The mission will not be started if the current waypoint is more distant than MIS_DIST_1WP from the home position. 0 - 3600 - s - - - GPS failure fixed roll angle - Roll in degrees during the loiter after the vehicle has lost GPS in an auto mode (e.g. mission or loiter). - 0.0 - 30.0 - deg + 10000 + m 1 - 0.5 + 100 - - Maximal horizontal distance from current position to first waypoint - Failsafe check to prevent running mission stored from previous flight at a new takeoff location. Set a value of zero or less to disable. The mission will not be started if the current waypoint is more distant than MIS_DIST_1WP from the current position. - -1 + + Maximal horizontal distance between waypoint + Failsafe check to prevent running missions which are way too big. Set a value of zero or less to disable. The mission will not be started if any distance between two subsequent waypoints is greater than MIS_DIST_WPS. + 0 10000 m 1 100 - - Landing abort min altitude - Minimum altitude above landing point that the vehicle will climb to after an aborted landing. Then vehicle will loiter in this altitude until further command is received. Only applies to fixed-wing vehicles. - 0 + + Minimum Loiter altitude + This is the minimum altitude the system will always obey. The intent is to stay out of ground effect. set to -1, if there shouldn't be a minimum loiter altitude + -1 + 80 m + 1 + 0.5 Enable yaw control of the mount. (Only affects multicopters and ROI mission items) @@ -4677,31 +4839,18 @@ Enable - - Timeout for a successful payload deployment acknowledgement - 0 - s - 1 - 1 - - Default take-off altitude - This is the relative altitude the system will take off to if not otherwise specified. + Take-off altitude + This is the minimum altitude the system will take off to. 0 + 80 m 1 0.5 - - Mission takeoff/landing required - Specifies if a mission has to contain a takeoff and/or mission landing. Validity of configured takeoffs/landings is checked independently of the setting here. - - No requirements - Require a takeoff - Require a landing - Require a takeoff and a landing - Require both a takeoff and a landing, or neither - + + Take-off waypoint required + If set, the mission feasibility checker will check for a takeoff waypoint on the mission. Max yaw error in degrees needed for waypoint heading acceptance @@ -4721,7 +4870,8 @@ 1 - Heading behavior in autonomous modes + Yaw mode + Specifies the heading in Auto. 0 4 @@ -4734,7 +4884,7 @@ Acceptance Radius - Default acceptance radius, overridden by acceptance radius of waypoint if set. For fixed wing the npfg switch distance is used for horizontal acceptance. + Default acceptance radius, overridden by acceptance radius of waypoint if set. For fixed wing the L1 turning distance is used for horizontal acceptance. 0.05 200.0 m @@ -4761,9 +4911,9 @@ 1 0.5 - + Loiter radius (FW only) - Default value of loiter radius in FW mode (e.g. for Loiter mode). + Default value of loiter radius for missions, Hold mode, Return mode, etc. (fixedwing only). 25 1000 m @@ -4779,14 +4929,6 @@ 1 0.5 - - Minimum Loiter altitude - This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this mode without specifying an altitude (e.g. through Loiter switch on RC). Doesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint ("Go to"). Set to a negative value to disable. - -1 - m - 1 - 0.5 - Set traffic avoidance mode Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders @@ -4798,39 +4940,19 @@ Position Hold mode - - Set NAV TRAFFIC AVOID horizontal distance - Defines a crosstrack horizontal distance + + Set NAV TRAFFIC AVOID RADIUS MANNED + Defines the Radius where NAV TRAFFIC AVOID is Called For Manned Aviation 500 m - - Set NAV TRAFFIC AVOID vertical distance + + Set NAV TRAFFIC AVOID RADIUS + Defines the Radius where NAV TRAFFIC AVOID is Called For Unmanned Aviation 10 500 m - - Estimated time until collision - Minimum acceptable time until collsion. Assumes constant speed over 3d distance. - 1 - 900000000 - s - - - Vehicle base weight - This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight. - kg - 1 - 0.5 - - - Vehicle gross weight - This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added or removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight. - kg - 1 - 0.1 - @@ -4842,6 +4964,14 @@ Roll/Pitch/Yaw + + Motor Ordering + Determines the motor ordering. This can be used for example in combination with a 4-in-1 ESC that assumes a motor ordering which is different from PX4. ONLY supported for Quads. When changing this, make sure to test the motor response without props first. + + PX4 + Betaflight / Cleanflight + + @@ -4855,20 +4985,6 @@ Stabilize yaw for absolute/lock mode. - - Pitch maximum when landed - -90.0 - 90.0 - deg - 1 - - - Pitch minimum when landed - -90.0 - 90.0 - deg - 1 - Auxiliary channel to control pitch (in AUX input or manual mode) 0 @@ -4921,71 +5037,78 @@ Mount input mode - This is the protocol used between the ground station and the autopilot. Recommended is Auto, RC only or MAVLink gimbal protocol v2. The rest will be deprecated. + RC uses the AUX input channels (see MNT_MAN_* parameters), MAVLINK_ROI uses the MAV_CMD_DO_SET_ROI Mavlink message, and MAVLINK_DO_MOUNT the MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL messages to control a mount. -1 4 true DISABLED - Auto (RC and MAVLink gimbal protocol v2) + AUTO RC - MAVLINK_ROI (protocol v1, to be deprecated) - MAVLINK_DO_MOUNT (protocol v1, to be deprecated) + MAVLINK_ROI (protocol v1) + MAVLINK_DO_MOUNT (protocol v1) MAVlink gimbal protocol v2 Mount output mode - This is the protocol used between the autopilot and a connected gimbal. Recommended is the MAVLink gimbal protocol v2 if the gimbal supports it. + AUX uses the mixer output Control Group #2. MAVLINK uses the MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL MavLink messages to control a mount (set MNT_MAV_SYSID & MNT_MAV_COMPID) 0 2 - true AUX MAVLink gimbal protocol v1 MAVLink gimbal protocol v2 - - Offset for pitch channel output in degrees - -360.0 - 360.0 - deg + + Mixer value for selecting a locking mode + if required for the gimbal (only in AUX output mode) + -1.0 + 1.0 + 3 + + + Mixer value for selecting normal mode + if required by the gimbal (only in AUX output mode) + -1.0 + 1.0 + 3 + + + Offset for pitch channel output in degrees + -360.0 + 360.0 1 Offset for roll channel output in degrees -360.0 360.0 - deg 1 Offset for yaw channel output in degrees -360.0 360.0 - deg 1 - + Range of pitch channel output in degrees (only in AUX output mode) 1.0 720.0 - deg 1 - + Range of roll channel output in degrees (only in AUX output mode) 1.0 720.0 - deg 1 Range of yaw channel output in degrees (only in AUX output mode) 1.0 720.0 - deg 1 @@ -4993,23 +5116,12 @@ Full stick input [-1..1] translats to [-pitch rate..pitch rate]. 1.0 90.0 - deg/s Angular yaw rate for manual input in degrees/second Full stick input [-1..1] translats to [-yaw rate..yaw rate]. 1.0 90.0 - deg/s - - - Input mode for RC gimbal input - 0 - 1 - - Angle - Angular rate - @@ -5065,19 +5177,19 @@ Yaw weight - A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. Deprioritizing yaw is necessary because multicopters have much less control authority in yaw compared to the other axes and it makes sense because yaw is not critical for stable hovering or 3D navigation. For yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain. + A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. Deprioritizing yaw is necessary because multicopters have much less control authority in yaw compared to the other axes and it makes sense because yaw is not critical for stable hovering or 3D navigation. For yaw control tuning use MC_YAW_P. This ratio has no inpact on the yaw gain. 0.0 1.0 2 0.1 - - Max yaw rate in autonomous modes - Limits the rate of change of the yaw setpoint to avoid large control output and mixer saturation. - 0 - 360 + + Max yaw rate in auto mode + Limit the rate of change of the yaw setpoint in autonomous mode to avoid large control output and mixer saturation. + 0.0 + 360.0 deg/s - 0 + 1 5 @@ -5115,42 +5227,42 @@ s 2 - - Maximum downwards acceleration in climb rate controlled modes - 2 - 15 + + Maximum vertical acceleration in velocity controlled modes down + 2.0 + 15.0 m/s^2 - 1 + 2 1 - - Acceleration for autonomous and for manual modes - When piloting manually, this parameter is only used in MPC_POS_MODE 4. - 2 - 15 + + Acceleration for auto and for manual + Note: In manual, this parameter is only used in MPC_POS_MODE 4. + 2.0 + 15.0 m/s^2 - 1 + 2 1 - - Maximum horizontal acceleration - MPC_POS_MODE 1 just deceleration 3 acceleration and deceleration 4 not used, use MPC_ACC_HOR instead - 2 - 15 + + Maximum horizontal acceleration for auto mode and for manual mode + MPC_POS_MODE 1 just deceleration 3 acceleration and deceleration 4 just acceleration + 2.0 + 15.0 m/s^2 2 1 - - Maximum upwards acceleration in climb rate controlled modes - 2 - 15 + + Maximum vertical acceleration in velocity controlled modes upward + 2.0 + 15.0 m/s^2 - 1 + 2 1 - Altitude reference mode + Altitude control mode Set to 0 to control height relative to the earth frame origin. This origin may move up and down in flight due to sensor drift. Set to 1 to control height relative to estimated distance to ground. The vehicle will move up and down with terrain height variation. Requires a distance to ground sensor. The height controller will revert to using height above origin if the distance to ground estimate becomes invalid as indicated by the local_position.distance_bottom_valid message being false. Set to 2 to control height relative to ground (requires a distance sensor) when stationary and relative to earth frame origin when moving horizontally. The speed threshold is controlled by the MPC_HOLD_MAX_XY parameter. 0 2 @@ -5161,96 +5273,59 @@ - Deadzone for sticks in manual piloted modes - Does not apply to manual throttle and direct attitude piloting by stick. - 0 - 1 + Deadzone of sticks where position hold is enabled + 0.0 + 1.0 2 - 0.01 Maximum horizontal velocity for which position hold is enabled (use 0 to disable check) - Only used with MPC_POS_MODE 0 or MPC_ALT_MODE 2 - 0 - 3 + 0.0 + 3.0 m/s 2 Maximum vertical velocity for which position hold is enabled (use 0 to disable check) - Only used with MPC_ALT_MODE 1 - 0 - 3 + 0.0 + 3.0 m/s 2 - - Jerk limit in autonomous modes - Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions but also limited agility. - 1 - 80 + + Jerk limit in auto mode + Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions, but it also limits its agility. + 1.0 + 80.0 m/s^3 1 1 - - Maximum horizontal and vertical jerk in Position/Altitude mode - Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother motions but limits agility (how fast it can change directions or break). Setting this to the maximum value essentially disables the limit. Only used with smooth MPC_POS_MODE 3 and 4. + + Maximum jerk limit + Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions, but it also limits its agility (how fast it can change directions or break). Setting this to the maximum value essentially disables the limit. Note: This is only used when MPC_POS_MODE is set to a smoothing mode 3 or 4. 0.5 - 500 + 500.0 m/s^3 - 0 + 2 1 - + Altitude for 1. step of slow landing (descend) - Below this altitude descending velocity gets limited to a value between "MPC_Z_VEL_MAX_DN" (or "MPC_Z_V_AUTO_DN") and "MPC_LAND_SPEED" Value needs to be higher than "MPC_LAND_ALT2" + Below this altitude descending velocity gets limited to a value between "MPC_Z_VEL_MAX_DN" and "MPC_LAND_SPEED" Value needs to be higher than "MPC_LAND_ALT2" 0 122 m 1 - + Altitude for 2. step of slow landing (landing) - Below this altitude descending velocity gets limited to "MPC_LAND_SPEED" Value needs to be lower than "MPC_LAND_ALT1" - 0 - 122 - m - 1 - - - Altitude for 3. step of slow landing - Below this altitude descending velocity gets limited to "MPC_LAND_CRWL", if LIDAR available. No effect if LIDAR not available + Below this altitude descending velocity gets limited to "MPC_LAND_SPEED". Value needs to be lower than "MPC_LAND_ALT1" 0 122 m 1 - - Land crawl descend rate - Used below MPC_LAND_ALT3 if distance sensor data is availabe. - 0.1 - m/s - 1 - - - User assisted landing radius - When nudging is enabled (see MPC_LAND_RC_HELP), this controls the maximum allowed horizontal displacement from the original landing point. - 0 - m - 0 - 1 - - - Enable nudging based on user input during autonomous land routine - Using stick input the vehicle can be moved horizontally and yawed. The descend speed is amended: stick full up - 0 stick centered - MPC_LAND_SPEED stick full down - 2 * MPC_LAND_SPEED Manual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE). - 0 - 1 - - Nudging disabled - Nudging enabled - - Landing descend rate 0.6 @@ -5258,116 +5333,117 @@ 1 - Minimum collective thrust in Stabilized mode - The value is mapped to the lowest throttle stick position in Stabilized mode. Too low collective thrust leads to loss of roll/pitch/yaw torque control authority. Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE). - 0 - 1 + Minimum manual thrust + Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust. With MC_AIRMODE set to 1, this can safely be set to 0. + 0.0 + 1.0 norm 2 0.01 - - Maximal tilt angle in Stabilized or Altitude mode - 0 - 90 + + Maximal tilt angle in manual or altitude mode + 0.0 + 90.0 deg - 0 - 1 + 1 - - Max manual yaw rate for Stabilized, Altitude, Position mode - 0 + + Max manual yaw rate + 0.0 400 deg/s - 0 - 10 + 1 Manual yaw rate input filter time constant - Not used in Stabilized mode Setting this parameter to 0 disables the filter - 0 - 5 + Setting this parameter to 0 disables the filter + 0.0 + 5.0 s 2 - 0.01 - Position/Altitude mode variant - The supported sub-modes are: 0 Sticks directly map to velocity setpoints without smoothing. Also applies to vertical direction and Altitude mode. Useful for velocity control tuning. 3 Sticks map to velocity but with maximum acceleration and jerk limits based on jerk optimized trajectory generator (different algorithm than 1). 4 Sticks map to acceleration and there's a virtual brake drag + Manual-Position control sub-mode + The supported sub-modes are: 0 Simple position control where sticks map directly to velocity setpoints without smoothing. Useful for velocity control tuning. 3 Smooth position control with maximum acceleration and jerk limits based on jerk optimized trajectory generator (different algorithm than 1). 4 Smooth position control where sticks map to acceleration and there's a virtual brake drag - Direct velocity - Smoothed velocity - Acceleration based + Simple position control + Smooth position control (Jerk optimized) + Acceleration based input + + Enforced delay between arming and takeoff + For altitude controlled modes the time from arming the motors until a takeoff is possible gets forced to be at least MPC_SPOOLUP_TIME seconds to ensure the motors and propellers can sppol up and reach idle speed before getting commanded to spin faster. This delay is particularly useful for vehicles with slow motor spin-up e.g. because of large propellers. + 0 + 10 + s + - Thrust curve mapping in Stabilized Mode - This parameter defines how the throttle stick input is mapped to collective thrust in Stabilized mode. In case the default is used ('Rescale to hover thrust'), the stick input is linearly rescaled, such that a centered stick corresponds to the hover throttle (see MPC_THR_HOVER). Select 'No Rescale' to directly map the stick 1:1 to the output. This can be useful in case the hover thrust is very low and the default would lead to too much distortion (e.g. if hover thrust is set to 20%, then 80% of the upper thrust range is squeezed into the upper half of the stick range). Note: In case MPC_THR_HOVER is set to 50%, the modes 0 and 1 are the same. + Thrust curve in Manual Mode + This parameter defines how the throttle stick input is mapped to commanded thrust in Manual/Stabilized flight mode. In case the default is used ('Rescale to hover thrust'), the stick input is linearly rescaled, such that a centered stick corresponds to the hover throttle (see MPC_THR_HOVER). Select 'No Rescale' to directly map the stick 1:1 to the output. This can be useful in case the hover thrust is very low and the default would lead to too much distortion (e.g. if hover thrust is set to 20%, 80% of the upper thrust range is squeezed into the upper half of the stick range). Note: In case MPC_THR_HOVER is set to 50%, the modes 0 and 1 are the same. Rescale to hover thrust No Rescale - Vertical thrust required to hover - Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE). Used for initialization of the hover thrust estimator (see MPC_USE_HTE). The estimated hover thrust is used as base for zero vertical acceleration in altitude control. The hover thrust is important for land detection to work correctly. + Hover thrust + Vertical thrust required to hover. This value is mapped to center stick for manual throttle control. With this value set to the thrust required to hover, transition from manual to Altitude or Position mode while hovering will occur with the throttle stick near center, which is then interpreted as (near) zero demand for vertical speed. This parameter is also important for the landing detection to work correctly. 0.1 0.8 norm 2 0.01 - - Maximum collective thrust in climb rate controlled modes - Limit allowed thrust e.g. for indoor test of overpowered vehicle. - 0 - 1 + + Maximum thrust in auto thrust control + Limit max allowed thrust + 0.0 + 1.0 norm 2 - 0.05 + 0.01 - Minimum collective thrust in climb rate controlled modes - Too low thrust leads to loss of roll/pitch/yaw torque control authority. With airmode enabled this parameters can be set to 0 while still keeping torque authority (see MC_AIRMODE). + Minimum collective thrust in auto thrust control + It's recommended to set it > 0 to avoid free fall with zero thrust. Note: Without airmode zero thrust leads to zero roll/pitch control authority. (see MC_AIRMODE) 0.05 - 0.5 + 1.0 norm 2 0.01 Horizontal thrust margin - Margin that is kept for horizontal control when higher priority vertical thrust is saturated. To avoid completely starving horizontal control with high vertical error. - 0 + Margin that is kept for horizontal control when prioritizing vertical thrust. To avoid completely starving horizontal control with high vertical error. + 0.0 0.5 norm 2 0.01 - + Maximum tilt angle in air - Absolute maximum for all velocity or acceleration controlled modes. Any higher value is truncated. - 20 - 89 + Limits maximum tilt in AUTO and POSCTRL modes during flight. + 20.0 + 89.0 deg - 0 - 1 + 1 - - Maximum tilt during inital takeoff ramp - Tighter tilt limit during takeoff to avoid tip over. - 5 - 89 + + Maximum tilt during landing + Limits maximum tilt angle on landing. + 10.0 + 89.0 deg - 0 - 1 + 1 - - Smooth takeoff ramp time constant - Increasing this value will make climb rate controlled takeoff slower. If it's too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp + + Position control smooth takeoff ramp time constant + Increasing this value will make automatic and manual takeoff slower. If it's too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp 0 5 - s Takeoff climb rate @@ -5377,86 +5453,62 @@ 2 - Hover thrust estimator - Disable to use the fixed parameter MPC_THR_HOVER Enable to use the hover thrust estimator + Hover thrust source selector + Set false to use the fixed parameter MPC_THR_HOVER Set true to use the value computed by the hover thrust estimator - Numerical velocity derivative low pass cutoff frequency - 0 + Low pass filter cut freq. for numerical velocity derivative + 0.0 10 Hz - 1 - 0.5 - - - Maximum horizontal velocity setpoint in Position mode - Must be smaller than MPC_XY_VEL_MAX. The maximum sideways and backward speed can be set differently using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively. - 3 - 20 - m/s - 1 - 1 - - - Maximum backward velocity in Position mode - If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. - -1 - 20 - m/s - 1 - 1 + 2 - - Maximum sideways velocity in Position mode - If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. - -1 - 20 + + Maximum horizontal velocity setpoint for manual controlled mode + If velocity setpoint larger than MPC_XY_VEL_MAX is set, then the setpoint will be capped to MPC_XY_VEL_MAX + 3.0 + 20.0 m/s - 1 + 2 1 - - Default horizontal velocity in autonomous modes - e.g. in Missions, RTL, Goto if the waypoint does not specify differently - 3 - 20 + + Maximum horizontal velocity in mission + Horizontal velocity used when flying autonomously in e.g. Missions, RTL, Goto. + 3.0 + 20.0 m/s - 0 + 2 1 - + Maximum horizontal error allowed by the trajectory generator The integration speed of the trajectory setpoint is linearly reduced with the horizontal position tracking error. When the error is above this parameter, the integration of the trajectory is stopped to wait for the drone. This value can be adjusted depending on the tracking capabilities of the vehicle. 0.1 - 10 + 10.0 1 - 1 Manual position control stick exponential curve sensitivity - The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve + The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve 0 1 2 - 0.01 Proportional gain for horizontal position error - Defined as corrective velocity in m/s per m position error - 0 - 2 + 0.0 + 2.0 2 - 0.1 Proportional gain for horizontal trajectory position error 0.1 - 1 + 1.0 1 - 0.1 - - Overall Horizontal Velocity Limit + + Overall Horizonal Velocity Limit If set to a value greater than zero, other parameters are automatically set (such as MPC_XY_VEL_MAX or MPC_VEL_MANUAL). If set to a negative value, the existing individual parameters are used. -20 20 @@ -5464,63 +5516,56 @@ 1 - Differential gain for horizontal velocity error - Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative + Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again + defined as correction acceleration in m/s^2 per m/s^2 velocity derivative 0.1 - 2 - 2 - 0.02 + 2.0 + 3 Integral gain for horizontal velocity error - Defined as correction acceleration in m/s^2 per m velocity integral Allows to eliminate steady state errors in disturbances like wind. - 0 - 60 - 2 - 0.02 + defined as correction acceleration in m/s^2 per m velocity integral Non-zero value allows to eliminate steady state errors in the presence of disturbances like wind. + 0.0 + 60.0 + 3 - + Maximum horizontal velocity - Absolute maximum for all velocity controlled modes. Any higher value is truncated. - 0 - 20 + Maximum horizontal velocity in AUTO mode. If higher speeds are commanded in a mission they will be capped to this velocity. + 0.0 + 20.0 m/s - 1 + 2 1 Proportional gain for horizontal velocity error - Defined as corrective acceleration in m/s^2 per m/s velocity error + defined as correction acceleration in m/s^2 per m/s velocity error 1.2 - 5 + 5.0 2 - 0.1 Manual control stick yaw rotation exponential curve - The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve + The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve 0 1 2 - 0.01 Manual control stick vertical exponential curve - The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve + The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve 0 1 2 - 0.01 - + Proportional gain for vertical position error - Defined as corrective velocity in m/s per m position error - 0.1 + 0.0 1.5 2 - 0.1 - + Overall Vertical Velocity Limit If set to a value greater than zero, other parameters are automatically set (such as MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED). If set to a negative value, the existing individual parameters are used. -3 @@ -5528,65 +5573,41 @@ 1 0.5 - + Differential gain for vertical velocity error - Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative - 0 - 2 - 2 - 0.02 + defined as correction acceleration in m/s^2 per m/s^2 velocity derivative + 0.0 + 2.0 + 3 - + Integral gain for vertical velocity error - Defined as corrective acceleration in m/s^2 per m velocity integral + defined as correction acceleration in m/s^2 per m velocity integral Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff. 0.2 - 3 - 2 - 0.1 + 3.0 + 3 - - Maximum descent velocity - Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP + + Maximum vertical descent velocity + Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL). 0.5 - 4 + 4.0 m/s - 1 - 0.1 - - Maximum ascent velocity - Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP + + Maximum vertical ascent velocity + Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL). 0.5 - 8 + 8.0 m/s 1 - 0.1 - + Proportional gain for vertical velocity error - Defined as corrective acceleration in m/s^2 per m/s velocity error - 2 - 15 + defined as correction acceleration in m/s^2 per m/s velocity error + 2.0 + 15.0 2 - 0.1 - - - Descent velocity in autonomous modes - For manual modes and offboard, see MPC_Z_VEL_MAX_DN - 0.5 - 4 - m/s - 1 - 0.5 - - - Ascent velocity in autonomous modes - For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP - 0.5 - 8 - m/s - 1 - 0.5 Responsiveness @@ -5647,14 +5668,14 @@ Acro mode SuperExpo factor for Roll and Pitch - SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect + SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect 0 0.95 2 Acro mode SuperExpo factor for Yaw - SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect + SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect 0 0.95 2 @@ -5819,767 +5840,2944 @@ Minimum motor rise time (slew rate limit) - Minimum time allowed for the motor input signal to pass through a range of 1000 PWM units. A value x means that the motor signal can only go from 1000 to 2000 PWM in minimum x seconds. Zero means that slew rate limiting is disabled. + Minimum time allowed for the motor input signal to pass through a range of 1000 PWM units. A value x means that the motor signal can only go from 1000 to 2000 PWM in maximum x seconds. Zero means that slew rate limiting is disabled. 0.0 s/(1000*PWM) - - S.BUS out - Set to 1 to enable S.BUS version 1 output instead of RSSI. + + PWM aux 1 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used + -1 + 2150 + us - - Thrust to motor control signal model parameter - Parameter used to model the nonlinear relationship between motor control signal (e.g. PWM) and static thrust. The model is: rel_thrust = factor * rel_signal^2 + (1-factor) * rel_signal, where rel_thrust is the normalized thrust between 0 and 1, and rel_signal is the relative motor control signal between 0 and 1. - 0.0 - 1.0 - 1 - 0.1 + + PWM aux 2 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used + -1 + 2150 + us - - - - Landing Target Timeout - Time after which the landing target is considered lost without any new measurements. - 0.0 - 50 - s - 1 - 0.5 - - - Final approach altitude - Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground. - 0.0 - 10 - m - 2 - 0.1 + + PWM aux 3 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used + -1 + 2150 + us - - Horizontal acceptance radius - Start descending if closer above landing target than this. - 0.0 - 10 - m - 2 - 0.1 + + PWM aux 4 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used + -1 + 2150 + us - - Maximum number of search attempts - Maximum number of times to search for the landing target if it is lost during the precision landing. - 0 - 100 + + PWM aux 5 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used + -1 + 2150 + us - - Search altitude - Altitude above home to which to climb when searching for the landing target. - 0.0 - 100 - m - 1 - 0.1 + + PWM aux 6 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used + -1 + 2150 + us - - Search timeout - Time allowed to search for the landing target before falling back to normal landing. - 0.0 - 100 - s - 1 - 0.1 + + PWM aux 7 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used + -1 + 2150 + us - - - - RC channel 10 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM aux 8 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used + -1 + 2150 + us - - RC channel 10 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM aux disarmed value + This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. + 0 + 2200 us - - RC channel 10 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM aux 1 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 us - - RC channel 10 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM aux 2 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 + us - - RC channel 10 trim - Mid point value - 800.0 - 2200.0 + + PWM aux 3 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 us - - RC channel 11 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM aux 4 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 + us - - RC channel 11 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM aux 5 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 us - - RC channel 11 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM aux 6 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 us - - RC channel 11 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM aux 7 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 + us - - RC channel 11 trim - Mid point value - 800.0 - 2200.0 + + PWM aux 8 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 us - - RC channel 12 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM aux maximum value + Set to 2000 for industry default or 2100 to increase servo travel. + 1600 + 2200 + us - - RC channel 12 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM aux 1 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used + -1 + 2150 us - - RC channel 12 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM aux 2 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used + -1 + 2150 us - - RC channel 12 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM aux 3 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used + -1 + 2150 + us - - RC channel 12 trim - Mid point value - 800.0 - 2200.0 + + PWM aux 4 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used + -1 + 2150 us - - RC channel 13 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM aux 5 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used + -1 + 2150 + us - - RC channel 13 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM aux 6 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used + -1 + 2150 us - - RC channel 13 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM aux 7 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used + -1 + 2150 us - - RC channel 13 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM aux 8 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used + -1 + 2150 + us - - RC channel 13 trim - Mid point value - 800.0 - 2200.0 + + PWM aux minimum value + Set to 1000 for industry default or 900 to increase servo travel. + 800 + 1400 us - - RC channel 14 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM aux 1 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used + -1 + 1600 + us - - RC channel 14 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM aux 2 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used + -1 + 1600 us - - RC channel 14 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM aux 3 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used + -1 + 1600 us - - RC channel 14 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM aux 4 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used + -1 + 1600 + us - - RC channel 14 trim - Mid point value - 800.0 - 2200.0 + + PWM aux 5 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used + -1 + 1600 us - - RC channel 15 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM aux 6 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used + -1 + 1600 + us - - RC channel 15 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM aux 7 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used + -1 + 1600 us - - RC channel 15 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM aux 8 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used + -1 + 1600 us - - RC channel 15 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM channels used as ESC outputs + Number representing the channels e.g. 134 - Channel 1, 3 and 4. Global e.g. PWM_AUX_MIN/MAX/DISARM limits only apply to these channels. + 0 + 123456789 - - RC channel 15 trim - Mid point value - 800.0 - 2200.0 - us + + PWM aux output frequency + Set to 400 for industry default or 1000 for high frequency ESCs. Set to 0 for Oneshot125. + -1 + 2000 + Hz - - RC channel 16 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM aux 1 rate + Set the default PWM output frequency for the aux outputs + 0 + 400 + Hz - - RC channel 16 maximum - Maximum value for this channel. - 1500.0 - 2200.0 - us + + PWM aux 1 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - RC channel 16 minimum - Minimum value for this channel. - 800.0 - 1500.0 - us + + PWM aux 2 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - RC channel 16 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM aux 3 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - RC channel 16 trim - Mid point value - 800.0 - 2200.0 + + PWM aux 4 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM aux 5 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM aux 6 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM aux 7 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM aux 8 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM aux 1 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM aux 2 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM aux 3 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM aux 4 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM aux 5 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM aux 6 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM aux 7 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM aux 8 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM extra 1 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used + -1 + 2150 us - - RC channel 17 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM extra 2 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used + -1 + 2150 + us - - RC channel 17 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM extra 3 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used + -1 + 2150 us - - RC channel 17 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM extra 4 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used + -1 + 2150 us - - RC channel 17 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM extra 5 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used + -1 + 2150 + us - - RC channel 17 trim - Mid point value - 800.0 - 2200.0 + + PWM extra 6 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used + -1 + 2150 us - - RC channel 18 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM extra 7 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used + -1 + 2150 + us - - RC channel 18 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM extra 8 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used + -1 + 2150 us - - RC channel 18 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM extra disarmed value + This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. + 0 + 2200 us - - RC channel 18 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM extra 1 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + 0 + 2150 + us - - RC channel 18 trim - Mid point value - 800.0 - 2200.0 + + PWM extra 2 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + 0 + 2150 us - - RC channel 1 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM extra 3 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + 0 + 2150 us - - RC channel 1 maximum - Maximum value for RC channel 1 - 1500.0 - 2200.0 + + PWM extra 4 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + 0 + 2150 us - - RC channel 1 minimum - Minimum value for RC channel 1 - 800.0 - 1500.0 + + PWM extra 5 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + 0 + 2150 us - - RC channel 1 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM extra 6 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + 0 + 2150 + us - - RC channel 1 trim - Mid point value - 800.0 - 2200.0 + + PWM extra 7 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + 0 + 2150 us - - RC channel 2 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM extra 8 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + 0 + 2150 us - - RC channel 2 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM extra maximum value + Set to 2000 for industry default or 2100 to increase servo travel. + 1600 + 2200 us - - RC channel 2 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM extra 1 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used + -1 + 2150 us - - RC channel 2 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM extra 2 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used + -1 + 2150 + us - - RC channel 2 trim - Mid point value - 800.0 - 2200.0 + + PWM extra 3 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used + -1 + 2150 us - - RC channel 3 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM extra 4 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used + -1 + 2150 us - - RC channel 3 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM extra 5 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used + -1 + 2150 us - - RC channel 3 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM extra 6 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used + -1 + 2150 us - - RC channel 3 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM extra 7 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used + -1 + 2150 + us - - RC channel 3 trim - Mid point value - 800.0 - 2200.0 + + PWM extra 8 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used + -1 + 2150 us - - RC channel 4 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM extra minimum value + Set to 1000 for industry default or 900 to increase servo travel. + 800 + 1400 us - - RC channel 4 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM extra 1 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used + -1 + 1600 us - - RC channel 4 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM extra 2 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used + -1 + 1600 us - - RC channel 4 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM extra 3 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used + -1 + 1600 + us - - RC channel 4 trim - Mid point value - 800.0 - 2200.0 + + PWM extra 4 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used + -1 + 1600 us - - RC channel 5 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM extra 5 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used + -1 + 1600 + us - - RC channel 5 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM extra 6 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used + -1 + 1600 us - - RC channel 5 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM extra 7 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used + -1 + 1600 us - - RC channel 5 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM extra 8 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used + -1 + 1600 + us - - RC channel 5 trim - Mid point value - 800.0 - 2200.0 + + PWM extra output frequency + Set to 400 for industry default or 1000 for high frequency ESCs. Set to 0 for Oneshot125. + -1 + 2000 + Hz + + + PWM extra 1 rate + Set the default PWM output frequency for the main outputs + 0 + 400 + Hz + + + PWM extra 1 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM extra 2 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM extra 3 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM extra 4 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM extra 5 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM extra 6 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM extra 7 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM extra 8 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM extra 1 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM extra 2 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM extra 3 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM extra 4 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM extra 5 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM extra 6 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM extra 7 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM extra 8 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 1 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 us - - RC channel 6 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM main 10 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 + us - - RC channel 6 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM main 11 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 us - - RC channel 6 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM main 12 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 us - - RC channel 6 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM main 13 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 + us - - RC channel 6 trim - Mid point value - 800.0 - 2200.0 + + PWM main 14 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 us - - RC channel 7 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM main 2 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 + us - - RC channel 7 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM main 3 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 us - - RC channel 7 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM main 4 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 us - - RC channel 7 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM main 5 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 + us - - RC channel 7 trim - Mid point value - 800.0 - 2200.0 + + PWM main 6 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 us - - RC channel 8 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM main 7 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 + us - - RC channel 8 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM main 8 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 us - - RC channel 8 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM main 9 disarmed value + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + -1 + 2150 us - - RC channel 8 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM main disarmed value + This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. + 0 + 2200 + us - - RC channel 8 trim - Mid point value - 800.0 - 2200.0 + + PWM main 1 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 us - - RC channel 9 dead zone - The +- range of this value around the trim value will be considered as zero. - 0.0 - 100.0 + + PWM main 10 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 + us - - RC channel 9 maximum - Maximum value for this channel. - 1500.0 - 2200.0 + + PWM main 11 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 us - - RC channel 9 minimum - Minimum value for this channel. - 800.0 - 1500.0 + + PWM main 12 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 us - - RC channel 9 reverse - Set to -1 to reverse channel. - -1.0 - 1.0 - - Reverse - Normal - + + PWM main 13 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 + us - - RC channel 9 trim - Mid point value - 800.0 - 2200.0 + + PWM main 14 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 us - - RC channel count - This parameter is used by Ground Station software to save the number of channels which were used during RC calibration. It is only meant for ground station use. - 0 - 18 + + PWM main 2 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 + us - - Failsafe channel PWM threshold - Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold. By default this is the throttle channel. Set to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event, but below the minimum PWM value for the channel during normal operation. Note: The default value of 0 disables the feature (it is below the expected range). - 0 - 2200 + + PWM main 3 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 us - - AUX1 Passthrough RC channel - Default function: Camera pitch - 0 - 18 - - Unassigned + + PWM main 4 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 + us + + + PWM main 5 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 + us + + + PWM main 6 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 + us + + + PWM main 7 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 + us + + + PWM main 8 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 + us + + + PWM main 9 failsafe value + This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + -1 + 2150 + us + + + PWM main maximum value + Set to 2000 for industry default or 2100 to increase servo travel. + 1600 + 2200 + us + + + PWM main 1 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 10 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 11 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 12 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 13 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 14 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 2 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 3 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 4 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 5 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 6 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 7 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 8 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main 9 maximum value + This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used + -1 + 2150 + us + + + PWM main minimum value + Set to 1000 for industry default or 900 to increase servo travel. + 800 + 1400 + us + + + PWM main 1 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 10 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 11 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 12 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 13 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 14 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 2 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 3 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 4 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 5 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 6 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 7 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 8 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM main 9 minimum value + This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used + -1 + 1600 + us + + + PWM channels used as ESC outputs + Number representing the channels e.g. 134 - Channel 1, 3 and 4. Global e.g. PWM_MAIN_MIN/MAX/DISARM limits only apply to these channels. + 0 + 123456789 + + + PWM main output frequency + Set to 400 for industry default or 1000 for high frequency ESCs. Set to 0 for Oneshot125. + -1 + 2000 + Hz + + + PWM main 1 rate + Set the default PWM output frequency for the main outputs + 0 + 400 + Hz + + + PWM main 1 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 10 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 11 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 12 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 13 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 14 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 2 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 3 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 4 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 5 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 6 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 7 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 8 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 9 reverse value + Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + PWM main 1 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 10 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 11 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 12 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 13 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 14 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 2 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 3 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 4 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 5 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 6 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 7 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 8 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + PWM main 9 trim value + Set to normalized offset + -0.2 + 0.2 + 2 + + + S.BUS out + Set to 1 to enable S.BUS version 1 output instead of RSSI. + + + Thrust to motor control signal model parameter + Parameter used to model the nonlinear relationship between motor control signal (e.g. PWM) and static thrust. The model is: rel_thrust = factor * rel_signal^2 + (1-factor) * rel_signal, where rel_thrust is the normalized thrust between 0 and 1, and rel_signal is the relative motor control signal between 0 and 1. + 0.0 + 1.0 + + + + + Landing Target Timeout + Time after which the landing target is considered lost without any new measurements. + 0.0 + 50 + s + 1 + 0.5 + + + Final approach altitude + Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground. + 0.0 + 10 + m + 2 + 0.1 + + + Horizontal acceptance radius + Start descending if closer above landing target than this. + 0.0 + 10 + m + 2 + 0.1 + + + Maximum number of search attempts + Maximum number of times to search for the landing target if it is lost during the precision landing. + 0 + 100 + + + Search altitude + Altitude above home to which to climb when searching for the landing target. + 0.0 + 100 + m + 1 + 0.1 + + + Search timeout + Time allowed to search for the landing target before falling back to normal landing. + 0.0 + 100 + s + 1 + 0.1 + + + + + Serial Configuration for FastRTPS + Configure on which serial port to run FastRTPS. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + + + + Serial Configuration for MAVLink + FastRTPS + Configure on which serial port to run MAVLink + FastRTPS. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + + + + + + RC channel 10 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 10 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 10 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 10 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 10 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 11 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 11 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 11 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 11 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 11 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 12 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 12 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 12 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 12 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 12 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 13 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 13 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 13 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 13 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 13 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 14 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 14 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 14 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 14 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 14 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 15 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 15 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 15 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 15 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 15 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 16 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 16 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 16 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 16 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 16 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 17 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 17 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 17 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 17 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 17 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 18 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 18 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 18 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 18 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 18 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 1 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + us + + + RC channel 1 maximum + Maximum value for RC channel 1 + 1500.0 + 2200.0 + us + + + RC channel 1 minimum + Minimum value for RC channel 1 + 800.0 + 1500.0 + us + + + RC channel 1 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 1 trim + Mid point value (same as min for throttle) + 800.0 + 2200.0 + us + + + RC channel 2 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + us + + + RC channel 2 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 2 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 2 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 2 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 3 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + us + + + RC channel 3 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 3 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 3 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 3 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 4 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + us + + + RC channel 4 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 4 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 4 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 4 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 5 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 5 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 5 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 5 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 5 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 6 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 6 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 6 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 6 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 6 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 7 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 7 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 7 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 7 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 7 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 8 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 8 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 8 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 8 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 8 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel 9 dead zone + The +- range of this value around the trim value will be considered as zero. + 0.0 + 100.0 + + + RC channel 9 maximum + Maximum value for this channel. + 1500.0 + 2200.0 + us + + + RC channel 9 minimum + Minimum value for this channel. + 800.0 + 1500.0 + us + + + RC channel 9 reverse + Set to -1 to reverse channel. + -1.0 + 1.0 + + Reverse + Normal + + + + RC channel 9 trim + Mid point value (has to be set to the same as min for throttle channel). + 800.0 + 2200.0 + us + + + RC channel count + This parameter is used by Ground Station software to save the number of channels which were used during RC calibration. It is only meant for ground station use. + 0 + 18 + + + Failsafe channel PWM threshold + Set to a value slightly above the PWM value assumed by throttle in a failsafe event, but ensure it is below the PWM value assumed by throttle during normal operation. Use RC_MAP_FAILSAFE to specify which channel is used to check. Note: The default value of 0 is below the epxed range and hence disables the feature. + 0 + 2200 + us + + + AUX1 Passthrough RC channel + Default function: Camera pitch + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + AUX2 Passthrough RC channel + Default function: Camera roll + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + AUX3 Passthrough RC channel + Default function: Camera azimuth / yaw + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + AUX4 Passthrough RC channel + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + AUX5 Passthrough RC channel + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + AUX6 Passthrough RC channel + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Failsafe channel mapping + Configures which channel is used by the receiver to indicate the signal was lost. Futaba receivers do report that way. If 0, whichever channel is mapped to throttle is used otherwise the value indicates the specific RC channel to use Use RC_FAILS_THR to set the threshold indicating lost signal. By default it's below the expected range and hence diabled. + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + PARAM1 tuning channel + Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel. Set to 0 to deactivate * + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + PARAM2 tuning channel + Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel. Set to 0 to deactivate * + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + PARAM3 tuning channel + Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel. Set to 0 to deactivate * + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Pitch control channel mapping + The channel index (starting from 1 for channel 1) indicates which channel should be used for reading pitch inputs from. A value of zero indicates the switch is not assigned. + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Roll control channel mapping + The channel index (starting from 1 for channel 1) indicates which channel should be used for reading roll inputs from. A value of zero indicates the switch is not assigned. + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Throttle control channel mapping + The channel index (starting from 1 for channel 1) indicates which channel should be used for reading throttle inputs from. A value of zero indicates the switch is not assigned. + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Yaw control channel mapping + The channel index (starting from 1 for channel 1) indicates which channel should be used for reading yaw inputs from. A value of zero indicates the switch is not assigned. + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + PWM input channel that provides RSSI + 0: do not read RSSI from input channel 1-18: read RSSI from specified input channel Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters. + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Max input value for RSSI reading + Only used if RC_RSSI_PWM_CHAN > 0 + 0 + 2000 + + + Min input value for RSSI reading + Only used if RC_RSSI_PWM_CHAN > 0 + 0 + 2000 + + + Pitch trim + The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. + -0.25 + 0.25 + 2 + 0.01 + + + Roll trim + The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. + -0.25 + 0.25 + 2 + 0.01 + + + Yaw trim + The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. + -0.25 + 0.25 + 2 + 0.01 + + + + + Threshold for selecting acro mode + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + Threshold for the arm switch + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + Threshold for selecting assist mode + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + Threshold for selecting auto mode + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + Threshold for the landing gear switch + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + Threshold for the kill switch + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + Threshold for selecting loiter mode + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + Threshold for the manual switch + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + Acro switch channel + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Arm switch channel + Use it to arm/disarm via switch instead of default throttle stick. If this is assigned, arming and disarming via stick is disabled. + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Flaps channel + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Single channel flight mode selection + If this parameter is non-zero, flight modes are only selected by this channel and are assigned to six slots. + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Landing gear switch channel + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Emergency Kill switch channel + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Loiter switch channel + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Manual switch channel mapping + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Mode switch channel mapping + This is the main flight mode selector. The channel index (starting from 1 for channel 1) indicates which channel should be used for deciding about the main mode. A value of zero indicates the switch is not assigned. + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Offboard switch channel + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Position Control switch channel + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Rattitude switch channel (deprecated) + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Return switch channel + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + Stabilize switch channel mapping + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + + + VTOL transition switch channel mapping + 0 + 18 + + Unassigned Channel 1 Channel 2 Channel 3 @@ -6600,1341 +8798,1620 @@ Channel 18 - - AUX2 Passthrough RC channel - Default function: Camera roll - 0 - 18 - - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 - + + Threshold for selecting offboard mode + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + Threshold for selecting posctl mode + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + Threshold for selecting return to launch mode + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + Threshold for the stabilize switch + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + Threshold for the VTOL transition switch + 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + -1 + 1 + + + + + Half-angle of the return mode altitude cone + Defines the half-angle of a cone centered around the destination position that affects the altitude at which the vehicle returns. + 0 + 90 + deg + + No cone, always climb to RTL_RETURN_ALT above destination. + 25 degrees half cone angle. + 45 degrees half cone angle. + 65 degrees half cone angle. + 80 degrees half cone angle. + Only climb to at least RTL_DESCEND_ALT above destination. + + + + Return mode loiter altitude + Descend to this altitude (above destination position) after return, and wait for time defined in RTL_LAND_DELAY. Land (i.e. slowly descend) from this altitude if autolanding allowed. + 2 + 100 + m + 1 + 0.5 + + + Return mode delay + Delay before landing (after initial descent) in Return mode. If set to -1 the system will not land but loiter at RTL_DESCEND_ALT. + -1 + 300 + s + 1 + 0.5 + + + Loiter radius for rtl descend + Set the radius for loitering to a safe altitude for VTOL transition. + 25 + 1000 + m + 1 + 0.5 + + + Horizontal radius from return point within which special rules for return mode apply + The return altitude will be calculated based on RTL_CONE_ANG parameter. The yaw setpoint will switch to the one defined by corresponding waypoint. + 0.5 + 100 + m + 1 + 0.5 + + + Return mode return altitude + Default minimum altitude above destination (e.g. home, safe point, landing pattern) for return flight. This is affected by RTL_MIN_DIST and RTL_CONE_ANG. + 0 + 150 + m + 1 + 0.5 + + + Return type + Return mode destination and flight path (home location, rally point, mission landing pattern, reverse mission) + + Return to closest safe point (home or rally point) via direct path. + Return to closest safe point other than home (mission landing pattern or rally point), via direct path. If no mission landing or rally points are defined return home via direct path. + Return to a planned mission landing, if available, using the mission path, else return to home via the reverse mission path. Do not consider rally points. + Return via direct path to closest destination: home, start of mission landing pattern or safe point. If the destination is a mission landing pattern, follow the pattern to land. + + + + + + RTL precision land mode + Use precision landing when doing an RTL landing phase. + + No precision landing + Opportunistic precision landing + Required precision landing + + + + + + Serial Configuration for Roboclaw Driver + Configure on which serial port to run Roboclaw Driver. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + + + + + + Address of the Roboclaw + The Roboclaw can be configured to have an address from 0x80 to 0x87, inclusive. It must be configured to match this parameter. + 128 + 135 + + 0x80 + 0x81 + 0x82 + 0x83 + 0x84 + 0x85 + 0x86 + 0x87 + + + + Roboclaw serial baud rate + Baud rate of the serial communication with the Roboclaw. The Roboclaw must be configured to match this rate. + 2400 + 460800 + true + + 2400 baud + 9600 baud + 19200 baud + 38400 baud + 57600 baud + 115200 baud + 230400 baud + 460800 baud + + + + Encoder counts per revolution + Number of encoder counts for one revolution. The roboclaw treats analog encoders (potentiometers) as having 2047 counts per rev. The default value of 1200 corresponds to the default configuration of the Aion R1 rover. + 1 + + + Encoder read period + How long to wait, in Milliseconds, between reading wheel encoder values over Uart from the Roboclaw + 1 + 1000 + ms + + + Uart write period + How long to wait, in Milliseconds, between writing actuator controls over Uart to the Roboclaw + 1 + 1000 + ms + + + + + L1 damping + Damping factor for L1 control. + 0.6 + 0.9 + 2 + 0.05 + + + L1 distance + This is the distance at which the next waypoint is activated. This should be set to about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy). + 1.0 + 50.0 + m + 1 + 0.1 + + + L1 period + This is the L1 distance and defines the tracking point ahead of the rover it's following. Use values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten slowly during tuning until response is sharp without oscillation. + 0.5 + 50.0 + m + 1 + 0.5 + + + Max manual yaw rate + 0.0 + 400 + deg/s + 1 + + + Maximum turn angle for Ackerman steering + At a control output of 0, the steering wheels are at 0 radians. At a control output of 1, the steering wheels are at GND_MAX_ANG radians. + 0.0 + 3.14159 + rad + 3 + 0.01 + + + Speed proportional gain + This is the derivative gain for the speed closed loop controller + 0.00 + 50.0 + %m/s + 3 + 0.005 + + + Speed Integral gain + This is the integral gain for the speed closed loop controller + 0.00 + 50.0 + %m/s + 3 + 0.005 + + + Speed integral maximum value + This is the maxim value the integral can reach to prevent wind-up. + 0.005 + 50.0 + %m/s + 3 + 0.005 - - AUX3 Passthrough RC channel - Default function: Camera azimuth / yaw - 0 - 18 - - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 - + + Maximum ground speed + 0.0 + 40 + m/s + 1 + 0.5 - - AUX4 Passthrough RC channel - 0 - 18 - - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 - + + Speed proportional gain + This is the proportional gain for the speed closed loop controller + 0.005 + 50.0 + %m/s + 3 + 0.005 - - AUX5 Passthrough RC channel + + Speed to throttle scaler + This is a gain to map the speed control output to the throttle linearly. + 0.005 + 50.0 + %m/s + 3 + 0.005 + + + Trim ground speed + 0.0 + 40 + m/s + 1 + 0.5 + + + Control mode for speed + This allows the user to choose between closed loop gps speed or open loop cruise throttle speed 0 - 18 + 1 - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + open loop control + close the loop with gps speed - - AUX6 Passthrough RC channel + + Cruise throttle + This is the throttle setting required to achieve the desired cruise speed. 10% is ok for a traxxas stampede vxl with ESC set to training mode + 0.0 + 1.0 + norm + 2 + 0.01 + + + Throttle limit max + This is the maximum throttle % that can be used by the controller. For a Traxxas stampede vxl with the ESC set to training, 30 % is enough + 0.0 + 1.0 + norm + 2 + 0.01 + + + Throttle limit min + This is the minimum throttle % that can be used by the controller. Set to 0 for rover + 0.0 + 1.0 + norm + 2 + 0.01 + + + Distance from front axle to rear axle + A value of 0.31 is typical for 1/10 RC cars. + 0.0 + m + 3 + 0.01 + + + + + Min airspeed scaling factor for takeoff + Pitch up will be commanded when the following airspeed is reached: FW_AIRSPD_MIN * RWTO_AIRSPD_SCL + 0.0 + 2.0 + norm + 2 + 0.01 + + + Specifies which heading should be held during runnway takeoff + 0: airframe heading, 1: heading towards takeoff waypoint 0 - 18 + 1 - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Airframe + Waypoint - - RC channel to engage the main motor (for helicopters) - 0 - 18 - - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 - + + Max pitch during takeoff + Fixed-wing settings are used if set to 0. Note that there is also a minimum pitch of 10 degrees during takeoff, so this must be larger if set. + 0.0 + 60.0 + deg + 1 + 0.5 + + + Max roll during climbout + Roll is limited during climbout to ensure enough lift and prevents aggressive navigation before we're on a safe height. + 0.0 + 60.0 + deg + 1 + 0.5 + + + Max throttle during runway takeoff + Can be used to test taxi on runway + 0.0 + 1.0 + norm + 2 + 0.01 + + + Altitude AGL at which we have enough ground clearance to allow some roll + Until RWTO_NAV_ALT is reached the plane is held level and only rudder is used to keep the heading (see RWTO_HDG). This should be below FW_CLMBOUT_DIFF if FW_CLMBOUT_DIFF > 0. + 0.0 + 100.0 + m + 1 + 1 + + + Pitch setpoint during taxi / before takeoff airspeed is reached + A taildragger with steerable wheel might need to pitch up a little to keep its wheel on the ground before airspeed to takeoff is reached. + -10.0 + 20.0 + deg + 1 + 0.5 + + + Throttle ramp up time for runway takeoff + 1.0 + 15.0 + s + 2 + 0.1 + + + Runway takeoff with landing gear - - Failsafe channel mapping - Configures which RC channel is used by the receiver to indicate the signal was lost (on receivers that use output a fixed signal value to report lost signal). If set to 0, the channel mapped to throttle is used. Use RC_FAILS_THR to set the threshold indicating lost signal. By default it's below the expected range and hence disabled. + + + + Battery-only Logging + When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes. + + + Maximum number of log directories to keep + If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files. 0 - 18 + 1000 + true + + + Mission Log + If enabled, a small additional "mission" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more). + true - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Disabled + All mission messages + Geotagging messages - - PARAM1 tuning channel - Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel. Set to 0 to deactivate * - 0 - 18 + + Logging Mode + Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. + true - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + disabled + when armed until disarm (default) + from boot until disarm + from boot until shutdown + depending on AUX1 RC channel - - PARAM2 tuning channel - Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel. Set to 0 to deactivate * + + Logging topic profile (integer bitmask) + This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug_*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and Magnetomer data) 7 : Topics for computer vision and collision avoidance 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 0 - 18 - - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 - + 1023 + true + + Default set (general log analysis) + Estimator replay (EKF2) + Thermal calibration + System identification + High rate + Debug + Sensor comparison + Computer Vision and Avoidance + Raw FIFO high-rate IMU (Gyro) + Raw FIFO high-rate IMU (Accel) + - - PARAM3 tuning channel - Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel. Set to 0 to deactivate * + + UTC offset (unit: min) + the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets + -1000 + 1000 + min + + + Log UUID + If set to 1, add an ID to the log, which uniquely identifies the vehicle + + + + + Simulator Battery drain interval + 1 + 86400 + s + 1 + + + Simulator Battery minimal percentage + Can be used to alter the battery level during SITL- or HITL-simulation on the fly. Particularly useful for testing different low-battery behaviour. 0 - 18 + 100 + % + 0.1 + + + + + ID of the Accelerometer that the calibration is for + + + Accelerometer 0 priority - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Uninitialized + Disabled + Min + Low + Medium (Default) + High + Max - - Pitch control channel mapping - The channel index (starting from 1 for channel 1) indicates which channel should be used for reading pitch inputs from. A value of zero indicates the switch is not assigned. - 0 - 18 + + Rotation of accelerometer 0 relative to airframe + An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. + -1 + 40 + true - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Internal + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + Roll 180° + Roll 180°, Yaw 45° + Roll 180°, Yaw 90° + Roll 180°, Yaw 135° + Pitch 180° + Roll 180°, Yaw 225° + Roll 180°, Yaw 270° + Roll 180°, Yaw 315° + Roll 90° + Roll 90°, Yaw 45° + Roll 90°, Yaw 90° + Roll 90°, Yaw 135° + Roll 270° + Roll 270°, Yaw 45° + Roll 270°, Yaw 90° + Roll 270°, Yaw 135° + Pitch 90° + Pitch 270° + Pitch 180°, Yaw 90° + Pitch 180°, Yaw 270° + Roll 90°, Pitch 90° + Roll 180°, Pitch 90° + Roll 270°, Pitch 90° + Roll 90°, Pitch 180° + Roll 270°, Pitch 180° + Roll 90°, Pitch 270° + Roll 180°, Pitch 270° + Roll 270°, Pitch 270° + Roll 90°, Pitch 180°, Yaw 90° + Roll 90°, Yaw 270° + Roll 90°, Pitch 68°, Yaw 293° + Pitch 315° + Roll 90°, Pitch 315° - - Roll control channel mapping - The channel index (starting from 1 for channel 1) indicates which channel should be used for reading roll inputs from. A value of zero indicates the switch is not assigned. - 0 - 18 - - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 - + + Accelerometer calibration temperature + Temperature during last calibration. + celcius - - Throttle control channel mapping - The channel index (starting from 1 for channel 1) indicates which channel should be used for reading throttle inputs from. A value of zero indicates the switch is not assigned. - 0 - 18 - - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 - + + Accelerometer X-axis offset - - Yaw control channel mapping - The channel index (starting from 1 for channel 1) indicates which channel should be used for reading yaw inputs from. A value of zero indicates the switch is not assigned. - 0 - 18 + + Accelerometer X-axis scaling factor + + + Accelerometer Y-axis offset + + + Accelerometer Y-axis scaling factor + + + Accelerometer Z-axis offset + + + Accelerometer Z-axis scaling factor + + + ID of the Accelerometer that the calibration is for + + + Accelerometer 1 priority - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Uninitialized + Disabled + Min + Low + Medium (Default) + High + Max - - PWM input channel that provides RSSI - 0: do not read RSSI from input channel 1-18: read RSSI from specified input channel Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters. - 0 - 18 + + Rotation of accelerometer 1 relative to airframe + An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. + -1 + 40 + true - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Internal + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + Roll 180° + Roll 180°, Yaw 45° + Roll 180°, Yaw 90° + Roll 180°, Yaw 135° + Pitch 180° + Roll 180°, Yaw 225° + Roll 180°, Yaw 270° + Roll 180°, Yaw 315° + Roll 90° + Roll 90°, Yaw 45° + Roll 90°, Yaw 90° + Roll 90°, Yaw 135° + Roll 270° + Roll 270°, Yaw 45° + Roll 270°, Yaw 90° + Roll 270°, Yaw 135° + Pitch 90° + Pitch 270° + Pitch 180°, Yaw 90° + Pitch 180°, Yaw 270° + Roll 90°, Pitch 90° + Roll 180°, Pitch 90° + Roll 270°, Pitch 90° + Roll 90°, Pitch 180° + Roll 270°, Pitch 180° + Roll 90°, Pitch 270° + Roll 180°, Pitch 270° + Roll 270°, Pitch 270° + Roll 90°, Pitch 180°, Yaw 90° + Roll 90°, Yaw 270° + Roll 90°, Pitch 68°, Yaw 293° + Pitch 315° + Roll 90°, Pitch 315° - - Max input value for RSSI reading - Only used if RC_RSSI_PWM_CHAN > 0 - 0 - 2000 + + Accelerometer calibration temperature + Temperature during last calibration. + celcius - - Min input value for RSSI reading - Only used if RC_RSSI_PWM_CHAN > 0 - 0 - 2000 + + Accelerometer X-axis offset - - Pitch trim - The trim value is the actuator control value the system needs for straight and level flight. - -0.5 - 0.5 - 2 - 0.01 + + Accelerometer X-axis scaling factor - - Roll trim - The trim value is the actuator control value the system needs for straight and level flight. - -0.5 - 0.5 - 2 - 0.01 + + Accelerometer Y-axis offset - - Yaw trim - The trim value is the actuator control value the system needs for straight and level flight. - -0.5 - 0.5 - 2 - 0.01 + + Accelerometer Y-axis scaling factor - - - - Threshold for the arm switch - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th - -1 - 1 + + Accelerometer Z-axis offset - - Threshold for selecting main motor engage - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th - -1 - 1 + + Accelerometer Z-axis scaling factor - - Threshold for the landing gear switch - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th - -1 - 1 + + ID of the Accelerometer that the calibration is for - - Threshold for the kill switch - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th + + Accelerometer 2 priority + + Uninitialized + Disabled + Min + Low + Medium (Default) + High + Max + + + + Rotation of accelerometer 2 relative to airframe + An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. -1 - 1 + 40 + true + + Internal + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + Roll 180° + Roll 180°, Yaw 45° + Roll 180°, Yaw 90° + Roll 180°, Yaw 135° + Pitch 180° + Roll 180°, Yaw 225° + Roll 180°, Yaw 270° + Roll 180°, Yaw 315° + Roll 90° + Roll 90°, Yaw 45° + Roll 90°, Yaw 90° + Roll 90°, Yaw 135° + Roll 270° + Roll 270°, Yaw 45° + Roll 270°, Yaw 90° + Roll 270°, Yaw 135° + Pitch 90° + Pitch 270° + Pitch 180°, Yaw 90° + Pitch 180°, Yaw 270° + Roll 90°, Pitch 90° + Roll 180°, Pitch 90° + Roll 270°, Pitch 90° + Roll 90°, Pitch 180° + Roll 270°, Pitch 180° + Roll 90°, Pitch 270° + Roll 180°, Pitch 270° + Roll 270°, Pitch 270° + Roll 90°, Pitch 180°, Yaw 90° + Roll 90°, Yaw 270° + Roll 90°, Pitch 68°, Yaw 293° + Pitch 315° + Roll 90°, Pitch 315° + + + + Accelerometer calibration temperature + Temperature during last calibration. + celcius + + + Accelerometer X-axis offset + + + Accelerometer X-axis scaling factor + + + Accelerometer Y-axis offset - - Threshold for selecting loiter mode - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th - -1 - 1 + + Accelerometer Y-axis scaling factor - - Acro switch channel (deprecated) - 0 - 18 - - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 - + + Accelerometer Z-axis offset - - Arm switch channel - Use it to arm/disarm via switch instead of default throttle stick. If this is assigned, arming and disarming via stick is disabled. - 0 - 18 - - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 - + + Accelerometer Z-axis scaling factor - - Flaps channel - 0 - 18 + + ID of the Accelerometer that the calibration is for + + + Accelerometer 3 priority - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Uninitialized + Disabled + Min + Low + Medium (Default) + High + Max - - Single channel flight mode selection - If this parameter is non-zero, flight modes are only selected by this channel and are assigned to six slots. - 0 - 18 + + Rotation of accelerometer 3 relative to airframe + An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. + -1 + 40 + true - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Internal + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + Roll 180° + Roll 180°, Yaw 45° + Roll 180°, Yaw 90° + Roll 180°, Yaw 135° + Pitch 180° + Roll 180°, Yaw 225° + Roll 180°, Yaw 270° + Roll 180°, Yaw 315° + Roll 90° + Roll 90°, Yaw 45° + Roll 90°, Yaw 90° + Roll 90°, Yaw 135° + Roll 270° + Roll 270°, Yaw 45° + Roll 270°, Yaw 90° + Roll 270°, Yaw 135° + Pitch 90° + Pitch 270° + Pitch 180°, Yaw 90° + Pitch 180°, Yaw 270° + Roll 90°, Pitch 90° + Roll 180°, Pitch 90° + Roll 270°, Pitch 90° + Roll 90°, Pitch 180° + Roll 270°, Pitch 180° + Roll 90°, Pitch 270° + Roll 180°, Pitch 270° + Roll 270°, Pitch 270° + Roll 90°, Pitch 180°, Yaw 90° + Roll 90°, Yaw 270° + Roll 90°, Pitch 68°, Yaw 293° + Pitch 315° + Roll 90°, Pitch 315° - - Button flight mode selection - This bitmask allows to specify multiple channels for changing flight modes using momentary buttons. Each channel is assigned to a mode slot ((lowest channel = slot 1). The resulting modes for each slot X is defined by the COM_FLTMODEX parameters. The functionality can be used only if RC_MAP_FLTMODE is disabled. The maximum number of available slots and hence bits set in the mask is 6. - 0 - 258048 - - Mask Channel 1 as a mode button - Mask Channel 2 as a mode button - Mask Channel 3 as a mode button - Mask Channel 4 as a mode button - Mask Channel 5 as a mode button - Mask Channel 6 as a mode button - Mask Channel 7 as a mode button - Mask Channel 8 as a mode button - Mask Channel 9 as a mode button - Mask Channel 10 as a mode button - Mask Channel 11 as a mode button - Mask Channel 12 as a mode button - Mask Channel 13 as a mode button - Mask Channel 14 as a mode button - Mask Channel 15 as a mode button - Mask Channel 16 as a mode button - Mask Channel 17 as a mode button - Mask Channel 18 as a mode button - + + Accelerometer calibration temperature + Temperature during last calibration. + celcius - - Landing gear switch channel - 0 - 18 - - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 - + + Accelerometer X-axis offset - - Emergency Kill switch channel - 0 - 18 + + Accelerometer X-axis scaling factor + + + Accelerometer Y-axis offset + + + Accelerometer Y-axis scaling factor + + + Accelerometer Z-axis offset + + + Accelerometer Z-axis scaling factor + + + ID of the Gyro that the calibration is for + + + Gyro 0 priority - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Uninitialized + Disabled + Min + Low + Medium (Default) + High + Max - - Loiter switch channel - 0 - 18 + + Rotation of gyro 0 relative to airframe + An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. + -1 + 40 + true - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Internal + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + Roll 180° + Roll 180°, Yaw 45° + Roll 180°, Yaw 90° + Roll 180°, Yaw 135° + Pitch 180° + Roll 180°, Yaw 225° + Roll 180°, Yaw 270° + Roll 180°, Yaw 315° + Roll 90° + Roll 90°, Yaw 45° + Roll 90°, Yaw 90° + Roll 90°, Yaw 135° + Roll 270° + Roll 270°, Yaw 45° + Roll 270°, Yaw 90° + Roll 270°, Yaw 135° + Pitch 90° + Pitch 270° + Pitch 180°, Yaw 90° + Pitch 180°, Yaw 270° + Roll 90°, Pitch 90° + Roll 180°, Pitch 90° + Roll 270°, Pitch 90° + Roll 90°, Pitch 180° + Roll 270°, Pitch 180° + Roll 90°, Pitch 270° + Roll 180°, Pitch 270° + Roll 270°, Pitch 270° + Roll 90°, Pitch 180°, Yaw 90° + Roll 90°, Yaw 270° + Roll 90°, Pitch 68°, Yaw 293° + Pitch 315° + Roll 90°, Pitch 315° - - Manual switch channel mapping (deprecated) - 0 - 18 - - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 - + + Gyroscope calibration temperature + Temperature during last calibration. + celcius - - Mode switch channel mapping (deprecated) - This is the main flight mode selector. The channel index (starting from 1 for channel 1) indicates which channel should be used for deciding about the main mode. A value of zero indicates the switch is not assigned. - 0 - 18 - - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 - + + Gyro X-axis offset - - Offboard switch channel - 0 - 18 + + Gyro Y-axis offset + + + Gyro Z-axis offset + + + ID of the Gyro that the calibration is for + + + Gyro 1 priority - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Uninitialized + Disabled + Min + Low + Medium (Default) + High + Max - - Position Control switch channel (deprecated) - 0 - 18 + + Rotation of gyro 1 relative to airframe + An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. + -1 + 40 + true - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Internal + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + Roll 180° + Roll 180°, Yaw 45° + Roll 180°, Yaw 90° + Roll 180°, Yaw 135° + Pitch 180° + Roll 180°, Yaw 225° + Roll 180°, Yaw 270° + Roll 180°, Yaw 315° + Roll 90° + Roll 90°, Yaw 45° + Roll 90°, Yaw 90° + Roll 90°, Yaw 135° + Roll 270° + Roll 270°, Yaw 45° + Roll 270°, Yaw 90° + Roll 270°, Yaw 135° + Pitch 90° + Pitch 270° + Pitch 180°, Yaw 90° + Pitch 180°, Yaw 270° + Roll 90°, Pitch 90° + Roll 180°, Pitch 90° + Roll 270°, Pitch 90° + Roll 90°, Pitch 180° + Roll 270°, Pitch 180° + Roll 90°, Pitch 270° + Roll 180°, Pitch 270° + Roll 270°, Pitch 270° + Roll 90°, Pitch 180°, Yaw 90° + Roll 90°, Yaw 270° + Roll 90°, Pitch 68°, Yaw 293° + Pitch 315° + Roll 90°, Pitch 315° - - Rattitude switch channel (deprecated) - 0 - 18 + + Gyroscope calibration temperature + Temperature during last calibration. + celcius + + + Gyro X-axis offset + + + Gyro Y-axis offset + + + Gyro Z-axis offset + + + ID of the Gyro that the calibration is for + + + Gyro 2 priority - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Uninitialized + Disabled + Min + Low + Medium (Default) + High + Max - - Return switch channel - 0 - 18 + + Rotation of gyro 2 relative to airframe + An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. + -1 + 40 + true - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Internal + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + Roll 180° + Roll 180°, Yaw 45° + Roll 180°, Yaw 90° + Roll 180°, Yaw 135° + Pitch 180° + Roll 180°, Yaw 225° + Roll 180°, Yaw 270° + Roll 180°, Yaw 315° + Roll 90° + Roll 90°, Yaw 45° + Roll 90°, Yaw 90° + Roll 90°, Yaw 135° + Roll 270° + Roll 270°, Yaw 45° + Roll 270°, Yaw 90° + Roll 270°, Yaw 135° + Pitch 90° + Pitch 270° + Pitch 180°, Yaw 90° + Pitch 180°, Yaw 270° + Roll 90°, Pitch 90° + Roll 180°, Pitch 90° + Roll 270°, Pitch 90° + Roll 90°, Pitch 180° + Roll 270°, Pitch 180° + Roll 90°, Pitch 270° + Roll 180°, Pitch 270° + Roll 270°, Pitch 270° + Roll 90°, Pitch 180°, Yaw 90° + Roll 90°, Yaw 270° + Roll 90°, Pitch 68°, Yaw 293° + Pitch 315° + Roll 90°, Pitch 315° - - Stabilize switch channel mapping (deprecated) - 0 - 18 + + Gyroscope calibration temperature + Temperature during last calibration. + celcius + + + Gyro X-axis offset + + + Gyro Y-axis offset + + + Gyro Z-axis offset + + + ID of the Gyro that the calibration is for + + + Gyro 3 priority - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Uninitialized + Disabled + Min + Low + Medium (Default) + High + Max - - VTOL transition switch channel mapping - 0 - 18 + + Rotation of gyro 3 relative to airframe + An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. + -1 + 40 + true - Unassigned - Channel 1 - Channel 2 - Channel 3 - Channel 4 - Channel 5 - Channel 6 - Channel 7 - Channel 8 - Channel 9 - Channel 10 - Channel 11 - Channel 12 - Channel 13 - Channel 14 - Channel 15 - Channel 16 - Channel 17 - Channel 18 + Internal + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + Roll 180° + Roll 180°, Yaw 45° + Roll 180°, Yaw 90° + Roll 180°, Yaw 135° + Pitch 180° + Roll 180°, Yaw 225° + Roll 180°, Yaw 270° + Roll 180°, Yaw 315° + Roll 90° + Roll 90°, Yaw 45° + Roll 90°, Yaw 90° + Roll 90°, Yaw 135° + Roll 270° + Roll 270°, Yaw 45° + Roll 270°, Yaw 90° + Roll 270°, Yaw 135° + Pitch 90° + Pitch 270° + Pitch 180°, Yaw 90° + Pitch 180°, Yaw 270° + Roll 90°, Pitch 90° + Roll 180°, Pitch 90° + Roll 270°, Pitch 90° + Roll 90°, Pitch 180° + Roll 270°, Pitch 180° + Roll 90°, Pitch 270° + Roll 180°, Pitch 270° + Roll 270°, Pitch 270° + Roll 90°, Pitch 180°, Yaw 90° + Roll 90°, Yaw 270° + Roll 90°, Pitch 68°, Yaw 293° + Pitch 315° + Roll 90°, Pitch 315° - - Threshold for selecting offboard mode - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th - -1 - 1 + + Gyroscope calibration temperature + Temperature during last calibration. + celcius - - Threshold for selecting return to launch mode - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th - -1 - 1 + + Gyro X-axis offset - - Threshold for the VTOL transition switch - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th - -1 - 1 + + Gyro Y-axis offset - - - - Half-angle of the return mode altitude cone - Defines the half-angle of a cone centered around the destination position that affects the altitude at which the vehicle returns. - 0 - 90 - deg - - No cone, always climb to RTL_RETURN_ALT above destination. - 25 degrees half cone angle. - 45 degrees half cone angle. - 65 degrees half cone angle. - 80 degrees half cone angle. - Only climb to at least RTL_DESCEND_ALT above destination. - + + Gyro Z-axis offset - - Return mode loiter altitude - Descend to this altitude (above destination position) after return, and wait for time defined in RTL_LAND_DELAY. Land (i.e. slowly descend) from this altitude if autolanding allowed. VTOLs do transition to hover in this altitdue above the landing point. - 0 - m - 1 - 0.5 + + ID of Magnetometer the calibration is for - - RTL heading mode - Defines the heading behavior during RTL + + Mag 0 priority - Towards next waypoint. - Heading matches destination. - Use current heading. + Uninitialized + Disabled + Min + Low + Medium (Default) + High + Max - - Return mode delay - Delay before landing (after initial descent) in Return mode. If set to -1 the system will not land but loiter at RTL_DESCEND_ALT. + + Rotation of magnetometer 0 relative to airframe + An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. -1 - s - 1 - 0.5 + 40 + true + + Internal + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + Roll 180° + Roll 180°, Yaw 45° + Roll 180°, Yaw 90° + Roll 180°, Yaw 135° + Pitch 180° + Roll 180°, Yaw 225° + Roll 180°, Yaw 270° + Roll 180°, Yaw 315° + Roll 90° + Roll 90°, Yaw 45° + Roll 90°, Yaw 90° + Roll 90°, Yaw 135° + Roll 270° + Roll 270°, Yaw 45° + Roll 270°, Yaw 90° + Roll 270°, Yaw 135° + Pitch 90° + Pitch 270° + Pitch 180°, Yaw 90° + Pitch 180°, Yaw 270° + Roll 90°, Pitch 90° + Roll 180°, Pitch 90° + Roll 270°, Pitch 90° + Roll 90°, Pitch 180° + Roll 270°, Pitch 180° + Roll 90°, Pitch 270° + Roll 180°, Pitch 270° + Roll 270°, Pitch 270° + Roll 90°, Pitch 180°, Yaw 90° + Roll 90°, Yaw 270° + Roll 90°, Pitch 68°, Yaw 293° + Pitch 315° + Roll 90°, Pitch 315° + - - Loiter radius for rtl descend - Set the radius for loitering to a safe altitude for VTOL transition. - 25 - m - 1 - 0.5 + + Magnetometer calibration temperature + Temperature during last calibration. + celcius - - Horizontal radius from return point within which special rules for return mode apply - The return altitude will be calculated based on RTL_CONE_ANG parameter. The yaw setpoint will switch to the one defined by corresponding waypoint. - 0.5 - m - 1 - 0.5 + + X Axis throttle compensation for Mag 0 + Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] - - RTL precision land mode - Use precision landing when doing an RTL landing phase. + + Magnetometer X-axis off diagonal factor + + + Magnetometer X-axis offset + + + Magnetometer X-axis scaling factor + + + Y Axis throttle compensation for Mag 0 + Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] + + + Magnetometer Y-axis off diagonal factor + + + Magnetometer Y-axis offset + + + Magnetometer Y-axis scaling factor + + + Z Axis throttle compensation for Mag 0 + Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] + + + Magnetometer Z-axis off diagonal factor + + + Magnetometer Z-axis offset + + + Magnetometer Z-axis scaling factor + + + ID of Magnetometer the calibration is for + + + Mag 1 priority - No precision landing - Opportunistic precision landing - Required precision landing + Uninitialized + Disabled + Min + Low + Medium (Default) + High + Max - - Return mode return altitude - Default minimum altitude above destination (e.g. home, safe point, landing pattern) for return flight. The vehicle will climb to this altitude when Return mode is enganged, unless it currently is flying higher already. This is affected by RTL_MIN_DIST and RTL_CONE_ANG. - 0 - m - 1 - 0.5 - - - Return type - Return mode destination and flight path (home location, rally point, mission landing pattern, reverse mission) + + Rotation of magnetometer 1 relative to airframe + An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. + -1 + 40 + true - Return to closest safe point (home or rally point) via direct path. - Return to closest safe point other than home (mission landing pattern or rally point), via direct path. If no mission landing or rally points are defined return home via direct path. Always chose closest safe landing point if vehicle is a VTOL in hover mode. - Return to a planned mission landing, if available, using the mission path, else return to home via the reverse mission path. Do not consider rally points. - Return via direct path to closest destination: home, start of mission landing pattern or safe point. If the destination is a mission landing pattern, follow the pattern to land. + Internal + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + Roll 180° + Roll 180°, Yaw 45° + Roll 180°, Yaw 90° + Roll 180°, Yaw 135° + Pitch 180° + Roll 180°, Yaw 225° + Roll 180°, Yaw 270° + Roll 180°, Yaw 315° + Roll 90° + Roll 90°, Yaw 45° + Roll 90°, Yaw 90° + Roll 90°, Yaw 135° + Roll 270° + Roll 270°, Yaw 45° + Roll 270°, Yaw 90° + Roll 270°, Yaw 135° + Pitch 90° + Pitch 270° + Pitch 180°, Yaw 90° + Pitch 180°, Yaw 270° + Roll 90°, Pitch 90° + Roll 180°, Pitch 90° + Roll 270°, Pitch 90° + Roll 90°, Pitch 180° + Roll 270°, Pitch 180° + Roll 90°, Pitch 270° + Roll 180°, Pitch 270° + Roll 270°, Pitch 270° + Roll 90°, Pitch 180°, Yaw 90° + Roll 90°, Yaw 270° + Roll 90°, Pitch 68°, Yaw 293° + Pitch 315° + Roll 90°, Pitch 315° - - - - RTL time estimate safety margin factor - Safety factor that is used to scale the actual RTL time estimate. Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN - 1.0 - 2.0 - 1 - 0.1 + + Magnetometer calibration temperature + Temperature during last calibration. + celcius - - RTL time estimate safety margin offset - Margin that is added to the time estimate, after it has already been scaled Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN - 0 - 3600 - s - 1 - 1 + + X Axis throttle compensation for Mag 1 + Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] - - - - L1 damping - Damping factor for L1 control. - 0.6 - 0.9 - 2 - 0.05 + + Magnetometer X-axis off diagonal factor - - L1 distance - This is the distance at which the next waypoint is activated. This should be set to about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy). - 1.0 - 50.0 - m - 1 - 0.1 + + Magnetometer X-axis offset - - L1 period - This is the L1 distance and defines the tracking point ahead of the rover it's following. Use values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten slowly during tuning until response is sharp without oscillation. - 0.5 - 50.0 - m - 1 - 0.5 + + Magnetometer X-axis scaling factor - - Max manual yaw rate - 0.0 - 400 - deg/s - 1 + + Y Axis throttle compensation for Mag 1 + Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] - - Maximum turn angle for Ackerman steering - At a control output of 0, the steering wheels are at 0 radians. At a control output of 1, the steering wheels are at GND_MAX_ANG radians. - 0.0 - 3.14159 - rad - 3 - 0.01 + + Magnetometer Y-axis off diagonal factor - - Speed proportional gain - This is the derivative gain for the speed closed loop controller - 0.00 - 50.0 - %m/s - 3 - 0.005 + + Magnetometer Y-axis offset - - Speed Integral gain - This is the integral gain for the speed closed loop controller - 0.00 - 50.0 - %m/s - 3 - 0.005 + + Magnetometer Y-axis scaling factor - - Speed integral maximum value - This is the maxim value the integral can reach to prevent wind-up. - 0.005 - 50.0 - %m/s - 3 - 0.005 + + Z Axis throttle compensation for Mag 1 + Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] - - Maximum ground speed - 0.0 - 40 - m/s - 1 - 0.5 + + Magnetometer Z-axis off diagonal factor - - Speed proportional gain - This is the proportional gain for the speed closed loop controller - 0.005 - 50.0 - %m/s - 3 - 0.005 + + Magnetometer Z-axis offset - - Speed to throttle scaler - This is a gain to map the speed control output to the throttle linearly. - 0.005 - 50.0 - %m/s - 3 - 0.005 + + Magnetometer Z-axis scaling factor - - Trim ground speed - 0.0 - 40 - m/s - 1 - 0.5 + + ID of Magnetometer the calibration is for - - Control mode for speed - This allows the user to choose between closed loop gps speed or open loop cruise throttle speed - 0 - 1 + + Mag 2 priority - open loop control - close the loop with gps speed + Uninitialized + Disabled + Min + Low + Medium (Default) + High + Max - - Cruise throttle - This is the throttle setting required to achieve the desired cruise speed. 10% is ok for a traxxas stampede vxl with ESC set to training mode - 0.0 - 1.0 - norm - 2 - 0.01 - - - Throttle limit max - This is the maximum throttle % that can be used by the controller. For a Traxxas stampede vxl with the ESC set to training, 30 % is enough - 0.0 - 1.0 - norm - 2 - 0.01 - - - Throttle limit min - This is the minimum throttle % that can be used by the controller. Set to 0 for rover - 0.0 - 1.0 - norm - 2 - 0.01 - - - Distance from front axle to rear axle - A value of 0.31 is typical for 1/10 RC cars. - 0.0 - m - 3 - 0.01 - - - - - Specifies which heading should be held during the runway takeoff ground roll - 0: airframe heading when takeoff is initiated 1: position control along runway direction (bearing defined from vehicle position on takeoff initiation to MAV_CMD_TAKEOFF position defined by operator) - 0 - 1 + + Rotation of magnetometer 2 relative to airframe + An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. + -1 + 40 + true - Airframe - Runway + Internal + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + Roll 180° + Roll 180°, Yaw 45° + Roll 180°, Yaw 90° + Roll 180°, Yaw 135° + Pitch 180° + Roll 180°, Yaw 225° + Roll 180°, Yaw 270° + Roll 180°, Yaw 315° + Roll 90° + Roll 90°, Yaw 45° + Roll 90°, Yaw 90° + Roll 90°, Yaw 135° + Roll 270° + Roll 270°, Yaw 45° + Roll 270°, Yaw 90° + Roll 270°, Yaw 135° + Pitch 90° + Pitch 270° + Pitch 180°, Yaw 90° + Pitch 180°, Yaw 270° + Roll 90°, Pitch 90° + Roll 180°, Pitch 90° + Roll 270°, Pitch 90° + Roll 90°, Pitch 180° + Roll 270°, Pitch 180° + Roll 90°, Pitch 270° + Roll 180°, Pitch 270° + Roll 270°, Pitch 270° + Roll 90°, Pitch 180°, Yaw 90° + Roll 90°, Yaw 270° + Roll 90°, Pitch 68°, Yaw 293° + Pitch 315° + Roll 90°, Pitch 315° - - Max throttle during runway takeoff - 0.0 - 1.0 - norm - 2 - 0.01 + + Magnetometer calibration temperature + Temperature during last calibration. + celcius - - NPFG period while steering on runway - 1.0 - 100.0 - s - 1 - 0.1 + + X Axis throttle compensation for Mag 2 + Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] - - Enable use of yaw stick for nudging the wheel during runway ground roll - This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course. Particularly useful for skinny runways or if the wheel servo is a bit off trim. + + Magnetometer X-axis off diagonal factor - - Pitch setpoint during taxi / before takeoff rotation airspeed is reached - A taildragger with steerable wheel might need to pitch up a little to keep its wheel on the ground before airspeed to takeoff is reached. - -10.0 - 20.0 - deg - 1 - 0.5 + + Magnetometer X-axis offset - - Throttle ramp up time for runway takeoff - 1.0 - 15.0 - s - 2 - 0.1 + + Magnetometer X-axis scaling factor - - Takeoff rotation airspeed - The calibrated airspeed threshold during the takeoff ground roll when the plane should start rotating (pitching up). Must be less than the takeoff airspeed, will otherwise be capped at the takeoff airpeed (see FW_TKO_AIRSPD). If set <= 0.0, defaults to 0.9 * takeoff airspeed (see FW_TKO_AIRSPD) - -1.0 - m/s - 1 - 0.1 + + Y Axis throttle compensation for Mag 2 + Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] - - Takeoff rotation time - This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation - 0.1 - s - 1 - 0.1 + + Magnetometer Y-axis off diagonal factor - - Runway takeoff with landing gear + + Magnetometer Y-axis offset - - - - Logfile Encryption algorithm - Selects the algorithm used for logfile encryption - - Disabled - XChaCha20 - AES - + + Magnetometer Y-axis scaling factor - - Battery-only Logging - When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes. + + Z Axis throttle compensation for Mag 2 + Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] + + + Magnetometer Z-axis off diagonal factor - - Maximum number of log directories to keep - If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files. - 0 - 1000 - true + + Magnetometer Z-axis offset - - Logfile Encryption key exchange key - If the logfile is encrypted using a symmetric key algorithm, the used encryption key is generated at logging start and stored on the sdcard RSA2048 encrypted using this key. - 0 - 255 + + Magnetometer Z-axis scaling factor - - Logfile Encryption key index - Selects the key in keystore, used for encrypting the log. When using a symmetric encryption algorithm, the key is generated at logging start and kept stored in this index. For symmetric algorithms, the key is volatile and valid only for the duration of logging. The key is stored in encrypted format on the sdcard alongside the logfile, using an RSA2048 key defined by the SDLOG_EXCHANGE_KEY - 0 - 255 + + ID of Magnetometer the calibration is for - - Mission Log - If enabled, a small additional "mission" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more). - true + + Mag 3 priority - Disabled - All mission messages - Geotagging messages + Uninitialized + Disabled + Min + Low + Medium (Default) + High + Max - - Logging Mode - Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. + + Rotation of magnetometer 3 relative to airframe + An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. + -1 + 40 true - disabled - when armed until disarm (default) - from boot until disarm - from boot until shutdown - depending on AUX1 RC channel - from 1st armed until shutdown + Internal + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + Roll 180° + Roll 180°, Yaw 45° + Roll 180°, Yaw 90° + Roll 180°, Yaw 135° + Pitch 180° + Roll 180°, Yaw 225° + Roll 180°, Yaw 270° + Roll 180°, Yaw 315° + Roll 90° + Roll 90°, Yaw 45° + Roll 90°, Yaw 90° + Roll 90°, Yaw 135° + Roll 270° + Roll 270°, Yaw 45° + Roll 270°, Yaw 90° + Roll 270°, Yaw 135° + Pitch 90° + Pitch 270° + Pitch 180°, Yaw 90° + Pitch 180°, Yaw 270° + Roll 90°, Pitch 90° + Roll 180°, Pitch 90° + Roll 270°, Pitch 90° + Roll 90°, Pitch 180° + Roll 270°, Pitch 180° + Roll 90°, Pitch 270° + Roll 180°, Pitch 270° + Roll 270°, Pitch 270° + Roll 90°, Pitch 180°, Yaw 90° + Roll 90°, Yaw 270° + Roll 90°, Pitch 68°, Yaw 293° + Pitch 315° + Roll 90°, Pitch 315° - - Logging topic profile (integer bitmask) - This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug_*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) 7 : Topics for computer vision and collision avoidance 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging) - 0 - 2047 - true - - Default set (general log analysis) - Estimator replay (EKF2) - Thermal calibration - System identification - High rate - Debug - Sensor comparison - Computer Vision and Avoidance - Raw FIFO high-rate IMU (Gyro) - Raw FIFO high-rate IMU (Accel) - Mavlink tunnel message logging - + + Magnetometer calibration temperature + Temperature during last calibration. + celcius - - UTC offset (unit: min) - the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets - -1000 - 1000 - min + + X Axis throttle compensation for Mag 3 + Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] - - Log UUID - If set to 1, add an ID to the log, which uniquely identifies the vehicle + + Magnetometer X-axis off diagonal factor - - - - Simulator Battery drain interval - 1 - 86400 - s - 1 + + Magnetometer X-axis offset - - Simulator Battery minimal percentage - Can be used to alter the battery level during SITL- or HITL-simulation on the fly. Particularly useful for testing different low-battery behaviour. - 0 - 100 - % - 0.1 + + Magnetometer X-axis scaling factor + + + Y Axis throttle compensation for Mag 3 + Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] + + + Magnetometer Y-axis off diagonal factor + + + Magnetometer Y-axis offset + + + Magnetometer Y-axis scaling factor + + + Z Axis throttle compensation for Mag 3 + Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] + + + Magnetometer Z-axis off diagonal factor + + + Magnetometer Z-axis offset + + + Magnetometer Z-axis scaling factor - - Type of magnetometer compensation @@ -7952,23 +10429,23 @@ Differential pressure sensor offset The offset (zero-reading) in Pascal - + Maximum height above ground when reliant on optical flow This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably. The height setpoint will be limited to be no greater than this value when the navigation system is completely reliant on optical flow data and the height above ground estimate is valid. The sensor may be usable above this height, but accuracy will progressively degrade. 1.0 - 100.0 + 25.0 m 1 0.1 - + Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground is less than 50% of this value. 1.0 rad/s 2 - + Minimum height above ground when reliant on optical flow This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably. The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus. 0.0 @@ -7979,11 +10456,6 @@ - - Enable external ADS1115 ADC - If enabled, the internal ADC is not used. - true - Capacity/current multiplier for high-current capable SMBUS battery 1 @@ -8038,9 +10510,20 @@ 2.00 m - - For legacy QGC support only - Use SENS_MAG_SIDES instead + + Automatically set external rotations + During calibration attempt to automatically determine the rotation of external magnetometers. + + + Bitfield selecting mag sides for calibration + If set to two side calibration, only the offsets are estimated, the scale calibration is left unchanged. Thus an initial six side calibration is recommended. Bits: ORIENTATION_TAIL_DOWN = 1 ORIENTATION_NOSE_DOWN = 2 ORIENTATION_LEFT = 4 ORIENTATION_RIGHT = 8 ORIENTATION_UPSIDE_DOWN = 16 ORIENTATION_RIGHTSIDE_UP = 32 + 34 + 63 + + Two side calibration + Three side calibration + Six side calibration + Low pass filter cutoff frequency for accel @@ -8070,14 +10553,7 @@ Hz true - - IMU gyro ESC notch filter bandwidth - Bandwidth per notch filter when using dynamic notch filtering with ESC RPM. - 5 - 30 - Hz - - + IMU gyro dynamic notch filtering Enable bank of dynamically updating notch filters. Requires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN). 0 @@ -8087,17 +10563,6 @@ FFT - - IMU gyro dynamic notch filter harmonics - ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering. - 1 - 7 - - - IMU gyro dynamic notch filter minimum frequency - Minimum notch filter frequency in Hz. - Hz - IMU gyro FFT enable true @@ -8113,52 +10578,31 @@ 4096 - + IMU gyro FFT maximum frequency 1 1000 Hz true - + IMU gyro FFT minimum frequency 1 1000 Hz true - - IMU gyro FFT SNR - 1 - 30 - - + Notch filter bandwidth for gyro - The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See "IMU_GYRO_NF0_FRQ" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers. + The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See "IMU_GYRO_NF_FREQ" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers. 0 100 Hz true - + Notch filter frequency for gyro - The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See "IMU_GYRO_NF0_BW" to set the bandwidth of the filter. A value of 0 disables the filter. - 0 - 1000 - Hz - true - - - Notch filter 1 bandwidth for gyro - The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See "IMU_GYRO_NF1_FRQ" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers. - 0 - 100 - Hz - true - - - Notch filter 2 frequency for gyro - The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See "IMU_GYRO_NF1_BW" to set the bandwidth of the filter. A value of 0 disables the filter. + The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See "IMU_GYRO_NF_BW" to set the bandwidth of the filter. A value of 0 disables the filter. 0 1000 Hz @@ -8194,41 +10638,6 @@ 400 Hz - - INA220 Power Monitor Config - 0 - 65535 - 1 - 1 - - - INA220 Power Monitor Battery Max Current - 0.1 - 500.0 - 2 - 0.1 - - - INA220 Power Monitor Regulator Max Current - 0.1 - 500.0 - 2 - 0.1 - - - INA220 Power Monitor Battery Shunt - 0.000000001 - 0.1 - 10 - .000000001 - - - INA220 Power Monitor Regulator Shunt - 0.000000001 - 0.1 - 10 - .000000001 - INA226 Power Monitor Config 0 @@ -8271,19 +10680,13 @@ 10 .000000001 - - INA238 Power Monitor Max Current - 0.1 - 327.68 - 2 - 0.1 - - - INA238 Power Monitor Shunt - 0.000000001 - 0.1 - 10 - .000000001 + + PCF8583 rotorfreq (i2c) i2c address + true + + Address 0x50 (80) + Address 0x51 (81) + PCF8583 rotorfreq (i2c) pulse count @@ -8299,60 +10702,23 @@ PCF8583 rotorfreq (i2c) pulse reset value - Internal device counter is reset to 0 when overrun this value, counter is able to store up to 6 digits reset of counter takes some time - measurement with reset has worse accuracy. 0 means reset counter after every measurement. + Internal device counter is reset to 0 when overun this value, counter is able to store upto 6 digits reset of counter takes some time - measurement with reset has worse accurancy. 0 means reset counter after every measurement. true - - AFBR Rangefinder Short/Long Range Threshold Hysteresis - This parameter defines the hysteresis for switching between short and long range mode. - 1 - 10 - m - - - AFBR Rangefinder Long Range Rate - This parameter defines measurement rate of the AFBR Rangefinder in long range mode. - 1 - 100 - - - AFBR Rangefinder Mode - This parameter defines the mode of the AFBR Rangefinder. - 0 - 3 - true - - Short Range Mode - Long Range Mode - High Speed Short Range Mode - High Speed Long Range Mode - - - - AFBR Rangefinder Short Range Rate - This parameter defines measurement rate of the AFBR Rangefinder in short range mode. - 1 - 100 - - - AFBR Rangefinder Short/Long Range Threshold - This parameter defines the threshold for switching between short and long range mode. The mode will switch from short to long range when the distance is greater than the threshold plus the hysteresis. The mode will switch from long to short range when the distance is less than the threshold minus the hysteresis. - 1 - 50 - m - QNH for barometer 500 1500 hPa + true Baro max rate - Barometric air data maximum publication rate. This is an upper bound, actual barometric data rate is still dependent on the sensor. + Barometric air data maximum publication rate. This is an upper bound, actual barometric data rate is still dependant on the sensor. 1 200 Hz + true Board rotation @@ -8419,36 +10785,39 @@ This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user to fine tune the board offset in the event of misalignment. deg - - Analog Devices ADIS16448 IMU (external SPI) - 0 - 1 - true - - Disabled - Enabled - - - - Analog Devices ADIS16507 IMU (external SPI) - true - - - Enable simulated airspeed sensor instance - 0 - 1 + + Serial Configuration for Lanbao PSK-CM8JL65-CC5 + Configure on which serial port to run Lanbao PSK-CM8JL65-CC5. true Disabled - Enabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + + + + Distance Sensor Rotation + Distance Sensor Rotation as MAV_SENSOR_ORIENTATION enum + True + + ROTATION_FORWARD_FACING + ROTATION_RIGHT_FACING + ROTATION_LEFT_FACING + ROTATION_BACKWARD_FACING + ROTATION_UPWARD_FACING + ROTATION_DOWNWARD_FACING - - ASP5033 differential pressure sensor (external I2C) - true - - - Enable simulated barometer sensor instance + + Analog Devices ADIS16448 IMU (external SPI) 0 1 true @@ -8465,21 +10834,6 @@ Eagle Tree airspeed sensor (external I2C) true - - Enable simulated GPS sinstance - 0 - 1 - true - - Disabled - Enabled - - - - Enable INA220 Power Monitor - For systems a INA220 Power Monitor, this should be set to true - true - Enable INA226 Power Monitor For systems a INA226 Power Monitor, this should be set to true @@ -8490,15 +10844,6 @@ For systems a INA228 Power Monitor, this should be set to true true - - Enable INA238 Power Monitor - For systems a INA238 Power Monitor, this should be set to true - true - - - IR-LOCK Sensor (external I2C) - true - Lidar-Lite (LL40LS) 0 @@ -8506,18 +10851,8 @@ true Disabled - PWM - I2C - - - - Enable simulated magnetometer sensor instance - 0 - 1 - true - - Disabled - Enabled + PWM + I2C @@ -8534,36 +10869,17 @@ Autodetect - - TE MS4515 differential pressure sensor (external I2C) - true - - - TE MS4525DO differential pressure sensor (external I2C) - true - - - TE MS5525DSO differential pressure sensor (external I2C) + + TE MS4525 differential pressure sensor (external I2C) true - - PAA3905 Optical Flow + + TE MS5525 differential pressure sensor (external I2C) true - PAW3902/PAW3903 Optical Flow - true - - - PCF8583 eneable driver - Run PCF8583 driver automatically - 0 - 1 + PAW3902 & PAW3903 Optical Flow true - - Disabled - Eneabled - PGA460 Ultrasonic driver (PGA460) @@ -8590,9 +10906,6 @@ SF10/b SF10/c SF11/c - SF30/b - SF30/c - LW20/c @@ -8608,25 +10921,12 @@ SF11/c SF/LW20/b SF/LW20/c - SF/LW30/d - - SHT3x temperature and hygrometer - true - - - Goertek SPL06 Barometer (external I2C) - true - HY-SRF05 / HC-SR05 true - - TF02 Pro Distance Sensor (i2c) - true - Thermal control of sensor temperature @@ -8649,10 +10949,6 @@ TREvo3m - - VL53L0X Distance Sensor - true - VL53L1X Distance Sensor true @@ -8661,17 +10957,10 @@ External I2C probe Probe for optional external I2C devices. - - Optical flow max rate - Optical flow data maximum publication rate. This is an upper bound, actual optical flow data rate is still dependent on the sensor. - 1 - 200 - Hz + + PX4Flow board rotation + This parameter defines the yaw rotation of the PX4FLOW board relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle. The recommneded installation default for the PX4FLOW board is with the Y axis forward (270 deg yaw). true - - - Optical flow rotation - This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle. No rotation Yaw 45° @@ -8683,7 +10972,7 @@ Yaw 315° - + Multi GPS Blending Control Mask Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. 0 : Set to true to use speed accuracy 1 : Set to true to use horizontal position accuracy 2 : Set to true to use vertical position accuracy 0 @@ -8708,10 +10997,6 @@ s 1 - - IMU auto calibration - Automatically initialize IMU (accel/gyro) calibration from bias estimates if available. - Sensors hub IMU mode true @@ -8753,13 +11038,23 @@ For systems with an external barometer, this should be set to false to make sure that the external is used. true - - Magnetometer auto calibration - Automatically initialize magnetometer calibration from bias estimate if available. - - - Automatically set external rotations - During calibration attempt to automatically determine the rotation of external magnetometers. + + Serial Configuration for LeddarOne Rangefinder + Configure on which serial port to run LeddarOne Rangefinder. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + Sensors hub mag mode @@ -8769,25 +11064,14 @@ Publish primary magnetometer - + Magnetometer max rate - Magnetometer data maximum publication rate. This is an upper bound, actual magnetometer data rate is still dependent on the sensor. + Magnetometer data maximum publication rate. This is an upper bound, actual magnetometer data rate is still dependant on the sensor. 1 200 Hz true - - Bitfield selecting mag sides for calibration - If set to two side calibration, only the offsets are estimated, the scale calibration is left unchanged. Thus an initial six side calibration is recommended. Bits: ORIENTATION_TAIL_DOWN = 1 ORIENTATION_NOSE_DOWN = 2 ORIENTATION_LEFT = 4 ORIENTATION_RIGHT = 8 ORIENTATION_UPSIDE_DOWN = 16 ORIENTATION_RIGHTSIDE_UP = 32 - 34 - 63 - - Two side calibration - Three side calibration - Six side calibration - - MaxBotix MB12XX Sensor 0 Rotation This parameter defines the rotation of the sensor relative to the platform. @@ -9206,17 +11490,79 @@ ROTATION_YAW_180 + + Serial Configuration for Lightware Laser Rangefinder (serial) + Configure on which serial port to run Lightware Laser Rangefinder (serial). + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + + Target IMU device ID to regulate temperature - - Dynamically simulate failure of airspeed sensor instance - 0 - 1 + + Serial Configuration for ThoneFlow-3901U optical flow sensor + Configure on which serial port to run ThoneFlow-3901U optical flow sensor. true Disabled - Enabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + + + + Serial Configuration for Benewake TFmini Rangefinder + Configure on which serial port to run Benewake TFmini Rangefinder. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + + + + Serial Configuration for uLanding Radar + Configure on which serial port to run uLanding Radar. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port @@ -9237,30 +11583,363 @@ - - MXS Serial Communication Baud rate - Baudrate for the Serial Port connected to the MXS Transponder - 0 - 10 + + Serial Configuration for RC Input Driver + Configure on which serial port to run RC Input Driver. Setting this to 'Disabled' will use a board-specific default port for RC input. true - 38400 - 600 - 4800 - 9600 - RESERVED - 57600 - 115200 - 230400 - 19200 - 460800 - 921600 + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + + + + Baudrate for the GPS 1 Serial Port + Configure the Baudrate for the GPS 1 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. + true + + Auto + 50 8N1 + 75 8N1 + 110 8N1 + 134 8N1 + 150 8N1 + 200 8N1 + 300 8N1 + 600 8N1 + 1200 8N1 + 1800 8N1 + 2400 8N1 + 4800 8N1 + 9600 8N1 + 19200 8N1 + 38400 8N1 + 57600 8N1 + 115200 8N1 + 230400 8N1 + 460800 8N1 + 500000 8N1 + 921600 8N1 + 1000000 8N1 + 1500000 8N1 + 2000000 8N1 + 3000000 8N1 + + + + Baudrate for the GPS 2 Serial Port + Configure the Baudrate for the GPS 2 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. + true + + Auto + 50 8N1 + 75 8N1 + 110 8N1 + 134 8N1 + 150 8N1 + 200 8N1 + 300 8N1 + 600 8N1 + 1200 8N1 + 1800 8N1 + 2400 8N1 + 4800 8N1 + 9600 8N1 + 19200 8N1 + 38400 8N1 + 57600 8N1 + 115200 8N1 + 230400 8N1 + 460800 8N1 + 500000 8N1 + 921600 8N1 + 1000000 8N1 + 1500000 8N1 + 2000000 8N1 + 3000000 8N1 + + + + Baudrate for the GPS 3 Serial Port + Configure the Baudrate for the GPS 3 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. + true + + Auto + 50 8N1 + 75 8N1 + 110 8N1 + 134 8N1 + 150 8N1 + 200 8N1 + 300 8N1 + 600 8N1 + 1200 8N1 + 1800 8N1 + 2400 8N1 + 4800 8N1 + 9600 8N1 + 19200 8N1 + 38400 8N1 + 57600 8N1 + 115200 8N1 + 230400 8N1 + 460800 8N1 + 500000 8N1 + 921600 8N1 + 1000000 8N1 + 1500000 8N1 + 2000000 8N1 + 3000000 8N1 + + + + Baudrate for the Radio Controller Serial Port + Configure the Baudrate for the Radio Controller Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. + true + + Auto + 50 8N1 + 75 8N1 + 110 8N1 + 134 8N1 + 150 8N1 + 200 8N1 + 300 8N1 + 600 8N1 + 1200 8N1 + 1800 8N1 + 2400 8N1 + 4800 8N1 + 9600 8N1 + 19200 8N1 + 38400 8N1 + 57600 8N1 + 115200 8N1 + 230400 8N1 + 460800 8N1 + 500000 8N1 + 921600 8N1 + 1000000 8N1 + 1500000 8N1 + 2000000 8N1 + 3000000 8N1 + + + + Baudrate for the TELEM 1 Serial Port + Configure the Baudrate for the TELEM 1 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. + true + + Auto + 50 8N1 + 75 8N1 + 110 8N1 + 134 8N1 + 150 8N1 + 200 8N1 + 300 8N1 + 600 8N1 + 1200 8N1 + 1800 8N1 + 2400 8N1 + 4800 8N1 + 9600 8N1 + 19200 8N1 + 38400 8N1 + 57600 8N1 + 115200 8N1 + 230400 8N1 + 460800 8N1 + 500000 8N1 + 921600 8N1 + 1000000 8N1 + 1500000 8N1 + 2000000 8N1 + 3000000 8N1 + + + + Baudrate for the TELEM 2 Serial Port + Configure the Baudrate for the TELEM 2 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. + true + + Auto + 50 8N1 + 75 8N1 + 110 8N1 + 134 8N1 + 150 8N1 + 200 8N1 + 300 8N1 + 600 8N1 + 1200 8N1 + 1800 8N1 + 2400 8N1 + 4800 8N1 + 9600 8N1 + 19200 8N1 + 38400 8N1 + 57600 8N1 + 115200 8N1 + 230400 8N1 + 460800 8N1 + 500000 8N1 + 921600 8N1 + 1000000 8N1 + 1500000 8N1 + 2000000 8N1 + 3000000 8N1 + + + + Baudrate for the TELEM 3 Serial Port + Configure the Baudrate for the TELEM 3 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. + true + + Auto + 50 8N1 + 75 8N1 + 110 8N1 + 134 8N1 + 150 8N1 + 200 8N1 + 300 8N1 + 600 8N1 + 1200 8N1 + 1800 8N1 + 2400 8N1 + 4800 8N1 + 9600 8N1 + 19200 8N1 + 38400 8N1 + 57600 8N1 + 115200 8N1 + 230400 8N1 + 460800 8N1 + 500000 8N1 + 921600 8N1 + 1000000 8N1 + 1500000 8N1 + 2000000 8N1 + 3000000 8N1 + + + + Baudrate for the TELEM/SERIAL 4 Serial Port + Configure the Baudrate for the TELEM/SERIAL 4 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. + true + + Auto + 50 8N1 + 75 8N1 + 110 8N1 + 134 8N1 + 150 8N1 + 200 8N1 + 300 8N1 + 600 8N1 + 1200 8N1 + 1800 8N1 + 2400 8N1 + 4800 8N1 + 9600 8N1 + 19200 8N1 + 38400 8N1 + 57600 8N1 + 115200 8N1 + 230400 8N1 + 460800 8N1 + 500000 8N1 + 921600 8N1 + 1000000 8N1 + 1500000 8N1 + 2000000 8N1 + 3000000 8N1 + + + + Baudrate for the UART 6 Serial Port + Configure the Baudrate for the UART 6 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. + true + + Auto + 50 8N1 + 75 8N1 + 110 8N1 + 134 8N1 + 150 8N1 + 200 8N1 + 300 8N1 + 600 8N1 + 1200 8N1 + 1800 8N1 + 2400 8N1 + 4800 8N1 + 9600 8N1 + 19200 8N1 + 38400 8N1 + 57600 8N1 + 115200 8N1 + 230400 8N1 + 460800 8N1 + 500000 8N1 + 921600 8N1 + 1000000 8N1 + 1500000 8N1 + 2000000 8N1 + 3000000 8N1 + + + + Baudrate for the Wifi Port Serial Port + Configure the Baudrate for the Wifi Port Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. + true + + Auto + 50 8N1 + 75 8N1 + 110 8N1 + 134 8N1 + 150 8N1 + 200 8N1 + 300 8N1 + 600 8N1 + 1200 8N1 + 1800 8N1 + 2400 8N1 + 4800 8N1 + 9600 8N1 + 19200 8N1 + 38400 8N1 + 57600 8N1 + 115200 8N1 + 230400 8N1 + 460800 8N1 + 500000 8N1 + 921600 8N1 + 1000000 8N1 + 1500000 8N1 + 2000000 8N1 + 3000000 8N1 + + Barometer offset in meters + Absolute value superior to 10000 will disable barometer + m + - distance sensor maximum range + distance sensor maximun range 0.0 1000.0 m @@ -9268,7 +11947,7 @@ 0.01 - distance sensor minimum range + distance sensor minimun range 0.0 10.0 m @@ -9276,13 +11955,18 @@ 0.01 - if >= 0 the distance sensor measures will be overridden by this value + if >= 0 the distance sensor measures will be overrided by this value Absolute value superior to 10000 will disable distance sensor m + + Number of GPS satellites used + 0 + 50 + Vehicle inertia about X axis - The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. + The intertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. 0.0 kg m^2 3 @@ -9290,21 +11974,21 @@ Vehicle cross term inertia xy - The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. + The intertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. kg m^2 3 0.005 Vehicle cross term inertia xz - The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. + The intertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. kg m^2 3 0.005 Vehicle inertia about Y axis - The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. + The intertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. 0.0 kg m^2 3 @@ -9312,14 +11996,14 @@ Vehicle cross term inertia yz - The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. + The intertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. kg m^2 3 0.005 Vehicle inertia about Z axis - The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. + The intertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. 0.0 kg m^2 3 @@ -9364,6 +12048,33 @@ 1800000000 deg*1e7 + + North magnetic field at the initial location + This value represents the North magnetic field at the initial location. A magnetic field calculator can be found on the NOAA website Note, the values need to be converted from nano Tesla to Gauss LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. + -1.0 + 1.0 + gauss + 2 + 0.001 + + + East magnetic field at the initial location + This value represents the East magnetic field at the initial location. A magnetic field calculator can be found on the NOAA website Note, the values need to be converted from nano Tesla to Gauss LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. + -1.0 + 1.0 + gauss + 2 + 0.001 + + + Down magnetic field at the initial location + This value represents the Down magnetic field at the initial location. A magnetic field calculator can be found on the NOAA website Note, the values need to be converted from nano Tesla to Gauss LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. + -1.0 + 1.0 + gauss + 2 + 0.001 + Pitch arm length This is the arm length generating the pitching moment This value can be measured with a ruler. This corresponds to half the distance between the front and rear motors. @@ -9380,6 +12091,21 @@ 2 0.05 + + magnetometer X offset in Gauss + Absolute value superior to 10000 will disable magnetometer + gauss + + + magnetometer Y offset in Gauss + Absolute value superior to 10000 will disable magnetometer + gauss + + + magnetometer Z offset in Gauss + Absolute value superior to 10000 will disable magnetometer + gauss + Vehicle mass This value can be measured by weighting the quad on a scale. @@ -9413,51 +12139,24 @@ Vehicle type true - Multicopter - Fixed-Wing - Tailsitter + MC + FW - - - simulated barometer pressure offset - - - simulated barometer temperature offset - celcius - - - simulated GPS number of satellites used + + + RGB Led brightness limit + Set to 0 to disable, 1 for minimum brightness up to 31 (max) 0 - 50 - - - simulator origin altitude - m - - - simulator origin latitude - deg - - - simulator origin longitude - deg - - - simulated magnetometer X offset - gauss - - - simulated magnetometer Y offset - gauss + 31 - - simulated magnetometer Z offset - gauss + + RGB Led brightness limit + Set to 0 to disable, 1 for minimum brightness up to 15 (max) + 0 + 15 - - Automatically configure default values Set to 1 to reset parameters on next system startup (setting defaults). Platform-specific values are used if available. RC* parameters are preserved. @@ -9498,7 +12197,7 @@ Required temperature rise during thermal calibration - A temperature increase greater than this value is required during calibration. Calibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL. If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit. + A temperature increase greater than this value is required during calibration. Calibration will complete for each sensor when the temperature increase above the starting temeprature exceeds the value set by SYS_CAL_TDEL. If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit. 10 celcius @@ -9512,23 +12211,9 @@ Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN. celcius - - Dataman storage backend - true - - Disabled - default (SD card) - RAM (not persistent) - - - + Enable factory calibration mode If enabled, future sensor calibrations will be stored to /fs/mtd_caldata. Note: this is only supported on boards with a separate calibration storage /fs/mtd_caldata. - - Disabled - All sensors - All sensors except mag - Enable failure injection @@ -9544,17 +12229,11 @@ Disable this if the system has no GPS. If disabled, the sensors hub will not process sensor_gps, and GPS will not be available for the rest of the system. true - + Control if the vehicle has a magnetometer - Set this to 0 if the board has no magnetometer. If set to 0, the preflight checks will not check for the presence of a magnetometer, otherwise N sensors are required. + Disable this if the board has no magnetometer, such as the Omnibus F4 SD. If disabled, the preflight checks will not check for the presence of a magnetometer. true - - Number of distance sensors to check being available - The preflight check will fail if fewer than this number of distance sensors with valid data is present. Disable the check with 0. - 0 - 4 - Enable HITL/SIH mode on next boot While enabled the system will boot in Hardware-In-The-Loop (HITL) or Simulation-In-Hardware (SIH) mode and not enable all sensors and checks. When disabled the same vehicle can be flown normally. Set to 'external HITL', if the system should perform as if it were a real vehicle (the only difference to a real system is then only the parameter value, which can be used for log analysis). @@ -9576,22 +12255,26 @@ Q attitude estimator (no position) - - RGB Led brightness limit - Set to 0 to disable, 1 for maximum brightness - % + + Set restart type + Set by px4io to indicate type of restart + 0 + 2 + + Data survives resets + Data survives in-flight resets only + Data does not survive reset + Enable stack checking - + Set usage of IO board - Can be used to use a configure the use of the IO board. + Can be used to use a standard startup script but with a FMU only set-up. Set to 0 to force the FMU only set-up. + 0 + 1 true - - IO PWM disabled (RC only) - IO enabled (RC & PWM) - @@ -9600,6 +12283,42 @@ If true, the FMU will try to connect to Blacksheep telemetry on start up true + + Serial Configuration for FrSky Telemetry + Configure on which serial port to run FrSky Telemetry. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + + + + Serial Configuration for HoTT Telemetry + Configure on which serial port to run HoTT Telemetry. + true + + Disabled + UART 6 + TELEM 1 + TELEM 2 + TELEM 3 + TELEM/SERIAL 4 + GPS 1 + GPS 2 + GPS 3 + Radio Controller + Wifi Port + + @@ -10159,249 +12878,21 @@ Gyro rate offset temperature ^2 polynomial coefficient - Y axis - Gyro rate offset temperature ^2 polynomial coefficient - Z axis - - - Gyro rate offset temperature ^3 polynomial coefficient - X axis - - - Gyro rate offset temperature ^3 polynomial coefficient - Y axis - - - Gyro rate offset temperature ^3 polynomial coefficient - Z axis - - - Thermal compensation for rate gyro sensors - true - - - ID of Magnetometer that the calibration is for - - - Magnetometer calibration maximum temperature - - - Magnetometer calibration minimum temperature - - - Magnetometer calibration reference temperature - - - Magnetometer offset temperature ^0 polynomial coefficient - X axis - - - Magnetometer offset temperature ^0 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^0 polynomial coefficient - Z axis - - - Magnetometer offset temperature ^1 polynomial coefficient - X axis - - - Magnetometer offset temperature ^1 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^1 polynomial coefficient - Z axis - - - Magnetometer offset temperature ^2 polynomial coefficient - X axis - - - Magnetometer offset temperature ^2 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^2 polynomial coefficient - Z axis - - - Magnetometer offset temperature ^3 polynomial coefficient - X axis - - - Magnetometer offset temperature ^3 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^3 polynomial coefficient - Z axis - - - ID of Magnetometer that the calibration is for - - - Magnetometer calibration maximum temperature - - - Magnetometer calibration minimum temperature - - - Magnetometer calibration reference temperature - - - Magnetometer offset temperature ^0 polynomial coefficient - X axis - - - Magnetometer offset temperature ^0 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^0 polynomial coefficient - Z axis - - - Magnetometer offset temperature ^1 polynomial coefficient - X axis - - - Magnetometer offset temperature ^1 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^1 polynomial coefficient - Z axis - - - Magnetometer offset temperature ^2 polynomial coefficient - X axis - - - Magnetometer offset temperature ^2 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^2 polynomial coefficient - Z axis - - - Magnetometer offset temperature ^3 polynomial coefficient - X axis - - - Magnetometer offset temperature ^3 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^3 polynomial coefficient - Z axis - - - ID of Magnetometer that the calibration is for - - - Magnetometer calibration maximum temperature - - - Magnetometer calibration minimum temperature - - - Magnetometer calibration reference temperature - - - Magnetometer offset temperature ^0 polynomial coefficient - X axis - - - Magnetometer offset temperature ^0 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^0 polynomial coefficient - Z axis - - - Magnetometer offset temperature ^1 polynomial coefficient - X axis - - - Magnetometer offset temperature ^1 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^1 polynomial coefficient - Z axis - - - Magnetometer offset temperature ^2 polynomial coefficient - X axis - - - Magnetometer offset temperature ^2 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^2 polynomial coefficient - Z axis - - - Magnetometer offset temperature ^3 polynomial coefficient - X axis - - - Magnetometer offset temperature ^3 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^3 polynomial coefficient - Z axis - - - ID of Magnetometer that the calibration is for - - - Magnetometer calibration maximum temperature - - - Magnetometer calibration minimum temperature - - - Magnetometer calibration reference temperature - - - Magnetometer offset temperature ^0 polynomial coefficient - X axis - - - Magnetometer offset temperature ^0 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^0 polynomial coefficient - Z axis - - - Magnetometer offset temperature ^1 polynomial coefficient - X axis - - - Magnetometer offset temperature ^1 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^1 polynomial coefficient - Z axis - - - Magnetometer offset temperature ^2 polynomial coefficient - X axis - - - Magnetometer offset temperature ^2 polynomial coefficient - Y axis - - - Magnetometer offset temperature ^2 polynomial coefficient - Z axis - - - Magnetometer offset temperature ^3 polynomial coefficient - X axis + Gyro rate offset temperature ^2 polynomial coefficient - Z axis - - Magnetometer offset temperature ^3 polynomial coefficient - Y axis + + Gyro rate offset temperature ^3 polynomial coefficient - X axis - - Magnetometer offset temperature ^3 polynomial coefficient - Z axis + + Gyro rate offset temperature ^3 polynomial coefficient - Y axis - - Thermal compensation for magnetometer sensors - true + + Gyro rate offset temperature ^3 polynomial coefficient - Z axis - - - - Sagetech External Configuration Mode - Disables auto-configuration mode enabling MXS config through external software. + + Thermal compensation for rate gyro sensors true - - Sagetech MXS mode configuration - This parameter defines the operating mode of the MXS - 0 - 3 - false - - Off - On - Standby - Alt - - - - Sagetech MXS Participant Configuration - The MXS communication port to receive Target data from - 0 - 2 - false - - Auto - COM0 - COM1 - - @@ -10409,26 +12900,22 @@ 20000 1000000 - - Enable MovingBaselineData publication - true - - - Enable MovingBaselineData subscription - 1 - true - - - Enable RTCM subscription - true + + UAVCAN Node ID + Read the specs at http://uavcan.org to learn more about Node ID. + 1 + 125 - - CAN built-in bus termination + + UAVCAN BATTERY_MONITOR battery monitor selection + This parameter defines that the system will select the battery monitor under the following conditions 0 - default battery monitor 1 - CUAV battery monitor + 0 1 - - - Simulator Gazebo bridge enable true + + default battery monitor + CUAV battery monitor + UAVCAN CAN bus bitrate @@ -10450,6 +12937,10 @@ Sensors and Actuators (ESCs) Automatic Config + + UAVCAN ESC will spin at idle throttle when armed, even if the mixer outputs zero setpoints + true + UAVCAN ANTI_COLLISION light operating mode This parameter defines the minimum condition under which the system will command the ANTI_COLLISION lights on 0 - Always off 1 - When autopilot is armed 2 - When autopilot is prearmed 3 - Always on @@ -10509,21 +13000,6 @@ 125 true - - publish Arming Status stream - Enable UAVCAN Arming Status stream publication uavcan::equipment::safety::ArmingStatus - true - - - publish moving baseline data RTCM stream - Enable UAVCAN RTCM stream publication ardupilot::gnss::MovingBaselineData - true - - - publish RTCM stream - Enable UAVCAN RTCM stream publication uavcan::equipment::gnss::RTCMStream - true - UAVCAN rangefinder maximum range This parameter defines the maximum valid range for a rangefinder connected via UAVCAN. @@ -10534,71 +13010,87 @@ This parameter defines the minimum valid range for a rangefinder connected via UAVCAN. m - - subscription airspeed - Enable UAVCAN airspeed subscriptions. uavcan::equipment::air_data::IndicatedAirspeed uavcan::equipment::air_data::TrueAirspeed uavcan::equipment::air_data::StaticTemperature + + + + UAVCAN/CAN v1 bus bitrate + 20000 + 1000000 + bit/s true - - subscription barometer - Enable UAVCAN barometer subscription. uavcan::equipment::air_data::StaticPressure uavcan::equipment::air_data::StaticTemperature + + UAVCAN v1 + 0 - UAVCAN disabled. 1 - Enables UAVCANv1 true - - subscription battery - Enable UAVCAN battery subscription. uavcan::equipment::power::BatteryInfo ardupilot::equipment::power::BatteryInfoAux 0 - Disable 1 - Use raw data. Recommended for Smart battery 2 - Filter the data with internal battery library - 0 - 2 - true - - Disable - Raw data - Filter data - + + actuator_outputs uORB over UAVCAN v1 publication port ID + -1 + 6143 - - subscription button - Enable UAVCAN button subscription. ardupilot::indication::Button - true + + DS-015 battery parameters subscription port ID + -1 + 6143 - - subscription differential pressure - Enable UAVCAN differential pressure subscription. uavcan::equipment::air_data::RawAirData - true + + DS-015 battery status subscription port ID + -1 + 6143 - - subscription flow - Enable UAVCAN optical flow subscription. - true + + DS-015 battery energy source subscription port ID + -1 + 6143 - - subscription GPS - Enable UAVCAN GPS subscriptions. uavcan::equipment::gnss::Fix uavcan::equipment::gnss::Fix2 uavcan::equipment::gnss::Auxiliary - true + + ESC 0 subscription port ID + -1 + 6143 - - subscription hygrometer - Enable UAVCAN hygrometer subscriptions. dronecan::sensors::hygrometer::Hygrometer - true + + UAVCAN v1 ESC publication port ID + -1 + 6143 - - subscription ICE - Enable UAVCAN internal combustion engine (ICE) subscription. uavcan::equipment::ice::reciprocating::Status - true + + GPS 0 subscription port ID + -1 + 6143 - - subscription IMU - Enable UAVCAN IMU subscription. uavcan::equipment::ahrs::RawIMU - true + + GPS 1 subscription port ID + -1 + 6143 - - subscription magnetometer - Enable UAVCAN mag subscription. uavcan::equipment::ahrs::MagneticFieldStrength uavcan::equipment::ahrs::MagneticFieldStrength2 - true + + UAVCAN v1 GPS publication port ID + -1 + 6143 + + + UAVCAN v1 leagcy battery port ID + -1 + 6143 + + + UAVCAN v1 Servo publication port ID + -1 + 6143 + + + sensor_gps uORB over UAVCAN v1 subscription port ID + -1 + 6143 - - subscription range finder - Enable UAVCAN range finder subscription. uavcan::equipment::range_sensor::Measurement + + + + UAVCAN v1 Node ID + Read the specs at http://uavcan.org to learn more about Node ID. + 1 + 125 true @@ -10693,36 +13185,51 @@ 2 1 - - Duration motor tilt up in backtransition - Time in seconds it takes to tilt form VT_TILT_FW to VT_TILT_MC. - 0.1 - 10 - s + + Backtransition deceleration setpoint to pitch feedforward gain + 0 + 0.2 + rad s^2/m 1 - 0.1 + 0.05 Backtransition deceleration setpoint to pitch I gain 0 0.3 rad s/m - 2 + 1 0.05 Approximate deceleration during back transition - Used to calculate back transition distance in an auto mode. For standard vtol and tiltrotors a controller is used to track this value during the transition. + The approximate deceleration during a back transition in m/s/s Used to calculate back transition distance in mission mode. A lower value will make the VTOL transition further from the destination waypoint. For standard vtol and tiltrotors a controller is used to track this value during the transition. 0.5 10 m/s^2 2 0.1 - - Maximum duration of a back transition - Transition is also declared over if the groundspeed drops below MPC_XY_CRUISE. - 0.1 + + Delay in seconds before applying back transition throttle + Set this to a value greater than 0 to give the motor time to spin down. unit s + 0 + 10 + 2 + 1 + + + Output on airbrakes channel during back transition + Used for airbrakes or with ESCs that have reverse thrust enabled on a seperate channel Airbrakes need to be enables for your selected model/mixer + 0 + 1 + 2 + 0.01 + + + Duration of a back transition + Time in seconds used for a back transition + 0.00 20.00 s 2 @@ -10734,192 +13241,168 @@ 0.0 20.0 s - 1 - 0.1 + + + Target throttle value for the transition to hover flight + standard vtol: pusher tailsitter, tiltrotor: main throttle Note for standard vtol: For ESCs and mixers that support reverse thrust on low PWM values set this to a negative value to apply active breaking For ESCs that support thrust reversal with a control channel please set VT_B_REV_OUT and set this to a positive value to apply active breaking + -1 + 1 + 2 + 0.01 + + + Maximum allowed angle the vehicle is allowed to pitch down to generate forward force + When fixed-wing forward actuation is active (see VT_FW_TRHUST_EN). If demanded down pitch exceeds this limmit, the fixed-wing forward actuators are used instead. + 0.0 + 45.0 - Lock control surfaces in hover - If set to 1 the control surfaces are locked at the disarmed value in multicopter mode. + Lock elevons in multicopter mode + If set to 1 the elevons are locked in multicopter mode - Use fixed-wing actuation in hover to accelerate forward - This feature can be used to avoid the plane having to pitch nose down in order to move forward. Prevents large, negative lift from pitching nose down into wind. Fixed-wing forward actuators refers to puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL). Only active if demanded down pitch is below VT_PITCH_MIN. Use VT_FWD_THRUST_SC to tune it. Only active (if enabled) in Altitude, Position and Auto modes, not in Stabilized. + Enable/disable usage of fixed-wing actuators in hover to generate forward force (instead of pitching down) + This technique can be used to avoid the plane having to pitch down in order to move forward. This prevents large, negative lift values being created when facing strong winds. Fixed-wing forward actuators refers to puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL). Only active if demaded down pitch is above VT_DWN_PITCH_MAX, and uses VT_FWD_THRUST_SC to get from demanded down pitch to fixed-wing actuation. - Disabled - Enabled (except LANDING) - Enabled if distance to ground above MPC_LAND_ALT1 - Enabled if distance to ground above MPC_LAND_ALT2 - Enabled constantly - Enabled if distance to ground above MPC_LAND_ALT1 (except LANDING) - Enabled if distance to ground above MPC_LAND_ALT2 (except LANDING) + Disable FW forward actuation in hover. + Enable FW forward actuation in hover in altitude, position and auto modes (except LANDING). + Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT1. + Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT2. + Enable FW forward actuation in hover in altitude, position and auto modes. + Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT1 (except LANDING). + Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT2 (except LANDING). - Fixed-wing actuation thrust scale for hover forward flight - Scale applied to the demanded down-pitch to get the fixed-wing forward actuation in hover mode. Enabled via VT_FWD_THRUST_EN. + Fixed-wing actuator thrust scale for hover forward flight + Scale applied to the demanded down-pitch to get the fixed-wing forward actuation in hover mode. Only active if demaded down pitch is above VT_DWN_PITCH_MAX. Enabled via VT_FWD_THRUST_EN. 0.0 2.0 - 2 - 0.01 + + + Adaptive QuadChute + Maximum negative altitude error for fixed wing flight. If the altitude drops below this value below the altitude setpoint the vehicle will transition back to MC mode and enter failsafe RTL. + 0.0 + 200.0 Differential thrust in forwards flight - Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode. The effectiveness of differential thrust around the corresponding axis can be tuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y. + Set to 1 to enable differential thrust in fixed-wing flight. 0 - 7 - - Yaw - Roll - Pitch - - - - Pitch differential thrust factor in forward flight - Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN. - 0.0 - 2.0 - 2 - 0.1 - - - Roll differential thrust factor in forward flight - Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN. - 0.0 - 2.0 - 2 - 0.1 + 1 + 0 - - Yaw differential thrust factor in forward flight - Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN. + + Differential thrust scaling factor + This factor specifies how the yaw input gets mapped to differential thrust in forwards flight. 0.0 - 2.0 + 1.0 2 0.1 - Quad-chute altitude - Minimum altitude for fixed-wing flight. When the vehicle is in fixed-wing mode and the altitude drops below this altitude (relative altitude above local origin), it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. + QuadChute Altitude + Minimum altitude for fixed wing flight, when in fixed wing the altitude drops below this altitude the vehicle will transition back to MC mode and enter failsafe RTL 0.0 200.0 - m - 1 - 1 - - Quad-chute maximum height - Maximum height above the ground (if available, otherwise above Home if available, otherwise above the local origin) where triggering a quad-chute is possible. At high altitudes there is a big risk to deplete the battery and therefore crash if quad-chuting there. + + The channel number of motors that must be turned off in fixed wing mode 0 - m + 12345678 + 0 1 + + Permanent stabilization in fw mode + If set to one this parameter will cause permanent attitude stabilization in fw mode. This parameter has been introduced for pure convenience sake. + - Quad-chute max pitch threshold - Absolute pitch threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold. + QuadChute Max Pitch + Maximum pitch angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL 0 180 - deg - Quad-chute max roll threshold - Absolute roll threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold. + QuadChute Max Roll + Maximum roll angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL 0 180 - deg Duration of a front transition Time in seconds used for a transition - 0.1 + 0.00 20.00 s 2 1 - Target throttle value for the transition to fixed-wing flight + Target throttle value for the transition to fixed wing flight + standard vtol: pusher tailsitter, tiltrotor: main throttle 0.0 1.0 3 0.01 - Airspeed-less front transition time (open loop) + Airspeed less front transition time (open loop) The duration of the front transition when there is no airspeed feedback available. 1.0 30.0 s - 1 - 0.5 - - - Minimum pitch angle during hover landing - Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering). During landing it can be beneficial to allow lower minimum pitch angles as it can avoid the wings generating too much lift and preventing the vehicle from sinking at the desired rate. - -10.0 - 45.0 - deg - 1 - 0.1 - - - Minimum pitch angle during hover - Any pitch setpoint below this value is translated to a forward force by the fixed-wing forward actuation if VT_FW_TRHUST_EN is set to 1. - -10.0 - 45.0 - deg - 1 - 0.1 - - - Pusher throttle ramp up slew rate - Defines the slew rate of the puller/pusher throttle during transitions. Zero will deactivate the slew rate limiting and thus produce an instant throttle rise to the transition throttle VT_F_TRANS_THR. - 0 - 1/s - 2 - 0.01 - - Quad-chute uncommanded descent threshold - Altitude error threshold for quad-chute triggering during fixed-wing flight. The check is only active if altitude is controlled and the vehicle is below the current altitude reference. The altitude error is relative to the highest altitude the vehicle has achieved since it has flown below the current altitude reference. Set to 0 do disable. - 0.0 - 200.0 - m - 1 + + Idle speed of VTOL when in multicopter mode + 900 + 2000 + us + 0 1 - - Quad-chute transition altitude loss threshold - Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight. Active until 5s after completing transition to fixed-wing. Only active if altitude estimate is valid and in altitude-controlled mode. If the current altitude is more than this value below the altitude at the beginning of the transition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold. + + Enable the usage of AUX outputs for hover motors + Set this parameter to true if the vehicle's hover motors are connected to the FMU (AUX) port. Not required for boards that only have a FMU, and no IO. Only applies for standard VTOL and tiltrotor. + + + The channel number of motors which provide lift during hover 0 - 50 - m - 1 + 12345678 + 0 1 - - Spoiler setting while landing (hover) - -1 - 1 - norm - 1 - 0.1 + + Pusher throttle ramp up window + Defines the time window during which the pusher throttle will be ramped up linearly to VT_F_TRANS_THR during a transition to fixed wing mode. Zero or negative values will produce an instant throttle rise to VT_F_TRANS_THR. + 20 + 2 + 0.01 - Normalized tilt in FW + Position of tilt servo in fw mode 0.0 1.0 3 0.01 - Normalized tilt in Hover + Position of tilt servo in mc mode + 0.0 + 1.0 + 3 + 0.01 + + + Tilt actuator control value commanded when disarmed and during the first second after arming + This specific tilt during spin-up is necessary for some systems whose motors otherwise don't spin-up freely. 0.0 1.0 3 0.01 - - Normalized tilt in transition to FW + + Position of tilt servo in transition mode 0.0 1.0 3 @@ -10931,12 +13414,10 @@ 0.0 20.0 s - 1 - 0.1 Duration of front transition phase 2 - Time in seconds it takes to tilt form VT_TILT_TRANS to VT_TILT_FW. + Time in seconds it should take for the rotors to rotate forward completely from the point when the plane has picked up enough airspeed and is ready to go into fixed wind mode. 0.1 5.0 s @@ -10946,7 +13427,7 @@ Front transition timeout Time in seconds after which transition will be cancelled. Disabled if set to 0. - 0.1 + 0.00 30.00 s 2 @@ -10956,6 +13437,7 @@ VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2) 0 2 + 0 true Tailsitter @@ -10973,18 +13455,73 @@ 0.01 - - - VTOL Takeoff relative loiter altitude - Altitude relative to home at which vehicle will loiter after front transition. - 20 - 300 - m - 1 - 1 + + + Inertia matrix, XX component + kg m^2 + 5 + 0.00001 + + + Inertia matrix, XY component + kg m^2 + 5 + 0.00001 + + + Inertia matrix, XZ component + kg m^2 + 5 + 0.00001 + + + Inertia matrix, YY component + kg m^2 + 5 + 0.00001 + + + Inertia matrix, YZ component + kg m^2 + 5 + 0.00001 + + + Inertia matrix, ZZ component + kg m^2 + 5 + 0.00001 + + + Mass + kg + 5 + 0.00001 + + EXFW_HDNG_P + + + EXFW_PITCH_P + + + EXFW_ROLL_P + + + Enable user assisted descent speed for autonomous land routine + When enabled, descent speed will be: stick full up - 0 stick centered - MPC_LAND_SPEED stick full down - 2 * MPC_LAND_SPEED + 0 + 1 + + Fixed descent speed of MPC_LAND_SPEED + User assisted descent speed + + + + RV_YAW_P + Skip the controller From 2abfbbcef01dbc16d4ee9e62e40b5acf1980360d Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Thu, 21 Sep 2023 14:00:13 +0000 Subject: [PATCH 055/118] Update PX4 Firmware metadata Thu Sep 21 14:00:13 UTC 2023 --- .../PX4/AirframeFactMetaData.xml | 822 +- .../PX4/PX4ParameterFactMetaData.xml | 11789 ++++++---------- 2 files changed, 4729 insertions(+), 7882 deletions(-) diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml index 60bd155a84e..b48dbc49ed3 100644 --- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml @@ -6,10 +6,10 @@ Airship Airship - starboard thruster - port thruster - thrust tilt - tail thruster + starboard thruster + port thruster + tail thruster + thrust tilt @@ -18,25 +18,23 @@ ThunderFly s.r.o., Roman Dvorak <dvorakroman@thunderfly.cz> Autogyro https://github.com/ThunderFly-aerospace/Auto-G2/ - rotor_head_L - rotor_head_R - elevator - rudder - rudder (second, optional) - throttle - wheel - feed-through of RC AUX1 channel for prerotator (optional) - feed-through of RC AUX2 channel for release device (optional) + throttle + rotor_head_L + rotor_head_R + elevator + rudder + rudder (second, optional) + wheel Autogyro ThunderFly s.r.o., Roman Dvorak <dvorakroman@thunderfly.cz> Autogyro https://github.com/ThunderFly-aerospace/TF-G2/ - rotor_head_L - rotor_head_R - rudder - throttle + throttle + rotor_head_L + rotor_head_R + rudder @@ -47,46 +45,17 @@ https://github.com/ThunderFly-aerospace/TF-B1/ - - - Copter - Emmanuel Roussel - Coaxial Helicopter - Left swashplate servomotor, pitch axis - Right swashplate servomotor, roll axis - Upper rotor (CCW) - Lower rotor (CW) - - Copter William Peale <develop707@gmail.com> Dodecarotor cox - motor 1 - motor 2 - motor 3 - motor 4 - motor 5 - motor 6 - motor 7 - motor 8 - motor 9 - motor 10 - motor 11 - motor 12 - + Copter - Bart Slinger <bartslinger@gmail.com> Helicopter - main motor - front swashplate servo - right swashplate servo - left swashplate servo - tail-rotor servo @@ -94,15 +63,6 @@ Copter Lorenz Meier <lorenz@px4.io> Hexarotor + - motor1 - motor2 - motor3 - motor4 - motor5 - motor6 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel @@ -110,15 +70,12 @@ Copter Lorenz Meier <lorenz@px4.io> Hexarotor Coaxial - front right top, CW - front right bottom, CCW - back top, CW - back bottom, CCW - front left top, CW - front left bottom, CCW - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel + front right top, CW + front right bottom, CCW + back top, CW + back bottom, CCW + front left top, CW + front left bottom, CCW @@ -126,48 +83,11 @@ Copter Lorenz Meier <lorenz@px4.io> Hexarotor x - motor 1 - motor 2 - motor 3 - motor 4 - motor 5 - motor 6 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel Copter Hyon Lim <lim@uvify.com> Hexarotor x - motor 1 - motor 2 - motor 3 - motor 4 - motor 5 - motor 6 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - - - Copter - Silvan Fuhrer - Hexarotor x - - - - - Copter - Simon Wilks <simon@uaventure.com> - Octo Coax Wide - motor 1 - motor 2 - motor 3 - motor 4 - motor 5 - motor 6 - motor 7 - motor 8 @@ -175,17 +95,6 @@ Copter Lorenz Meier <lorenz@px4.io> Octorotor + - motor 1 - motor 2 - motor 3 - motor 4 - motor 5 - motor 6 - motor 7 - motor 8 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel @@ -193,14 +102,14 @@ Copter Lorenz Meier <lorenz@px4.io> Octorotor Coaxial - motor 1 - motor 2 - motor 3 - motor 4 - motor 5 - motor 6 - motor 7 - motor 8 + motor 1 + motor 2 + motor 3 + motor 4 + motor 5 + motor 6 + motor 7 + motor 8 @@ -208,17 +117,6 @@ Copter Lorenz Meier <lorenz@px4.io> Octorotor x - motor 1 - motor 2 - motor 3 - motor 4 - motor 5 - motor 6 - motor 7 - motor 8 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel @@ -226,16 +124,6 @@ Copter Lorenz Meier <lorenz@px4.io> Quadrotor + - motor 1 - motor 2 - motor 3 - motor 4 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - feed-through of RC FLAPS channel @@ -243,95 +131,11 @@ Copter Blankered Quadrotor H - motor 1 - motor 2 - motor 3 - motor 4 - 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 - - - - - Copter - Lorenz Meier <lorenz@px4.io> - Quadrotor Wide - motor 1 - motor 2 - motor 3 - motor 4 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - feed-through of RC FLAPS channel - - - Copter - Lorenz Meier <lorenz@px4.io> - Quadrotor Wide - motor 1 - motor 2 - motor 3 - motor 4 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - feed-through of RC FLAPS channel - - - Copter - Lorenz Meier <lorenz@px4.io> - Quadrotor Wide - motor 1 - motor 2 - motor 3 - motor 4 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - feed-through of RC FLAPS channel - - - Copter - Simon Wilks <simon@uaventure.com> - Quadrotor Wide - motor 1 - motor 2 - motor 3 - motor 4 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - feed-through of RC FLAPS channel - - - - - Copter - Lorenz Meier <lorenz@px4.io> - Quadrotor asymmetric - https://docs.px4.io/master/en/frames_multicopter/spedix_s250_pixracer.html - motor1 (front right: CCW) - motor2 (back left: CCW) - motor3 (front left: CW) - motor4 (back right: CW) - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel @@ -339,36 +143,6 @@ Copter Lorenz Meier <lorenz@px4.io> Quadrotor x - motor 1 - motor 2 - motor 3 - motor 4 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - feed-through of RC FLAPS channel - - - Copter - James Goppert <james.goppert@gmail.com> - Quadrotor x - - - Copter - Lorenz Meier <lorenz@px4.io> - Quadrotor x - - - Copter - Lorenz Meier <lorenz@px4.io> - Quadrotor x - - - Copter - Lorenz Meier <lorenz@px4.io> - Quadrotor x Copter @@ -380,36 +154,22 @@ Lorenz Meier <lorenz@px4.io> Quadrotor x - + Copter Quadrotor x - motor 1 - motor 2 - motor 3 - motor 4 Copter Iain Galloway <iain.galloway@nxp.com> Quadrotor x - motor 1 - motor 2 - motor 3 - motor 4 - + Copter - Silvan Fuhrer + Farhang Naderi <farhang.nba@gmail.com> Quadrotor x - + Copter - Andreas Antener <andreas@uaventure.com> - Quadrotor x - - - Copter - Lorenz Meier <lorenz@px4.io> Quadrotor x @@ -421,72 +181,27 @@ Copter Beat Kueng <beat-kueng@gmx.net> Quadrotor x - https://docs.px4.io/master/en/frames_multicopter/holybro_qav250_pixhawk4_mini.html + https://docs.px4.io/main/en/frames_multicopter/holybro_qav250_pixhawk4_mini.html Copter Beat Kueng <beat@px4.io> Quadrotor x - - Copter - James Goppert <james.goppert@gmail.com> - Quadrotor x - Copter Quadrotor x - motor 1 - motor 2 - motor 3 - motor 4 Copter Hyon Lim <lim@uvify.com> Quadrotor x - motor 1 - motor 2 - motor 3 - motor 4 - - - Copter - Hyon Lim <lim@uvify.com> - Quadrotor x - motor 1 - motor 2 - motor 3 - motor 4 Copter Hyon Lim <lim@uvify.com> Quadrotor x - motor 1 - motor 2 - motor 3 - motor 4 - - - Copter - Anton Matosov <anton.matosov@gmail.com> - Quadrotor x - - - Copter - Henry Zhang <zhanghui629@gmail.com> - Quadrotor x - - - Copter - Matt McFadden <matt.mcfadden@tealdrones.com> - Quadrotor x - motor 1 - motor 2 - motor 3 - motor 4 Copter @@ -504,7 +219,7 @@ Quadrotor x - + Copter Lorenz Meier <lorenz@px4.io> @@ -516,158 +231,20 @@ Simulation - - - Copter - Ricardo Marques <marques.ricardo17@gmail.com> - Tilt-Quad - http://www.alivaero.com/the-project.html - motor 1 - motor 2 - motor 3 - motor 4 - Outer servo motor for rotor 2 arm - Outer servo motor for rotor 4 arm - Inner servo motor for rotor 2 arm - Inner servo motor for rotor 4 arm - - - + Copter - Trent Lukaczyk <aerialhedgehog@gmail.com> Tricopter Y+ - motor 1 - motor 2 - motor 3 - yaw servo - - - - - Copter - Trent Lukaczyk <aerialhedgehog@gmail.com> - Tricopter Y- - motor 1 - motor 2 - motor 3 - yaw servo + motor 1 + motor 2 + motor 3 + yaw servo - - Plane - - Flying Wing - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Plane - Simon Wilks <simon@uaventure.com> - Flying Wing - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - + Plane - Simon Wilks <simon@uaventure.com> Flying Wing - https://docs.px4.io/master/en/frames_plane/wing_wing_z84.html - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Plane - Julian Oes <julian@px4.io> - Flying Wing - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Plane - Lorenz Meier <lorenz@px4.io> - Flying Wing - https://docs.px4.io/master/en/frames_plane/wing_wing_z84.html - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Plane - Simon Wilks <simon@uaventure.com> - Flying Wing - right aileron - left aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Plane - Simon Wilks <simon@uaventure.com> - Flying Wing - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Plane - Simon Wilks <simon@uaventure.com> - Flying Wing - http://www.sparkletech.hk/ - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Plane - Jan Liphardt <JTLiphardt@gmail.com> - Flying Wing - - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Plane - Lorenz Meier <lorenz@px4.io> - Flying Wing - left aileron - right aileron - throttle - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel @@ -675,49 +252,17 @@ Plane Andreas Antener <andreas@uaventure.com> Plane A-Tail - aileron right - aileron left - v-tail right - v-tail left - throttle - wheel - flaps right - flaps left - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - - - Plane - Friedrich Beckmann <friedrich.beckmann@hs-augsburg.de> - Plane V-Tail - aileron right - aileron left - v-tail right - v-tail left - throttle - wheel - flaps right - flaps left - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel + throttle + aileron right + aileron left + v-tail right + v-tail left + wheel + flaps right + flaps left - - - Plane - Lorenz Meier <lorenz@px4.io> - Simulation - aileron - elevator - rudder - throttle - flaps - gear - + Plane Romain Chiappinelli <romain.chiap@gmail.com> @@ -725,59 +270,30 @@ - + Plane - Lorenz Meier <lorenz@px4.io> Standard Plane - aileron - elevator - throttle - rudder - flaps - gear - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - - - Plane - Andreas Antener <andreas@uaventure.com> - Standard Plane - aileron - aileron - elevator - rudder - throttle - wheel - flaps - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - + Rover Rover - steering - throttle + throttle + steering - + Rover - Timothy Scott Rover https://www.aionrobotics.com/r1 - Speed of left wheels - Speed of right wheels Rover Katrin Moritz Rover - Steering servo - Speed of left wheels - Speed of right wheels + Speed of left wheels + Steering servo @@ -797,14 +313,25 @@ Underwater Robot Thies Lennart Alff <thies.lennart.alff@tuhh.de> Vectored 6 DOF UUV - motor 1 CCW, bow starboard horizontal, , propeller CCW - motor 2 CCW, bow port horizontal, propeller CCW - motor 3 CCW, stern starboard horizontal, propeller CW - motor 4 CCW, stern port horizontal, propeller CW - motor 5 CCW, bow starboard vertical, propeller CCW - motor 6 CCW, bow port vertical, propeller CW - motor 7 CCW, stern starboard vertical, propeller CW - motor 8 CCW, stern port vertical, propeller CCW + motor 1 CCW, bow starboard horizontal, , propeller CCW + motor 2 CCW, bow port horizontal, propeller CCW + motor 3 CCW, stern starboard horizontal, propeller CW + motor 4 CCW, stern port horizontal, propeller CW + motor 5 CCW, bow starboard vertical, propeller CCW + motor 6 CCW, bow port vertical, propeller CW + motor 7 CCW, stern starboard vertical, propeller CW + motor 8 CCW, stern port vertical, propeller CCW + + + + + VTOL + Romain Chiappinelli <romain.chiap@gmail.com> + Simulation + motor right + motor left + elevon right + elevon left @@ -813,197 +340,52 @@ Roman Bapst <roman@auterion.com> Standard VTOL - + VTOL - - Standard VTOL - motor 1 - motor 2 - motor 3 - motor 4 - Aileron 1 - Aileron 2 - Elevator - Rudder - Throttle - - - VTOL - Simon Wilks <simon@uaventure.com> - Standard VTOL - motor 1 - motor 2 - motor 3 - motor 4 - Aileron 1 - Aileron 2 - Elevator - Rudder - Throttle - - - VTOL - Simon Wilks <simon@uaventure.com> - Standard VTOL - motor 1 - motor 2 - motor 3 - motor 4 - Right elevon - Left elevon - Motor - - - VTOL - Sander Smeets <sander@droneslab.com> - Standard VTOL - - - VTOL - Sander Smeets <sander@droneslab.com> - Standard VTOL - - - VTOL - Andreas Antener <andreas@uaventure.com> Standard VTOL VTOL Sander Smeets <sander@droneslab.com> Standard VTOL - motor 1 - motor 2 - motor 3 - motor 4 - Right elevon - Left elevon - Pusher motor - Pusher reverse channel + motor 1 + motor 2 + motor 3 + motor 4 + Right elevon + Left elevon + Pusher motor + Pusher reverse channel VTOL Silvan Fuhrer <silvan@auterion.com> Standard VTOL - Ailerons - A-tail left - Pusher motor - A-tail right - motor 1 - motor 2 - motor 3 - motor 4 - - - - - VTOL - Roman Bapst <roman@px4.io> - VTOL Duo Tailsitter - motor right - motor left - elevon right - elevon left - - + motor 1 + motor 2 + motor 3 + motor 4 + Pusher motor + Ailerons + A-tail left + A-tail right + + + + VTOL - Roman Bapst <roman@px4.io> - VTOL Duo Tailsitter - motor right - motor left - elevon right - elevon left - - - - - VTOL - VTOL Octoplane - motor 1 - motor 2 - motor 3 - motor 4 - motor 5 - motor 6 - motor 7 - motor 8 - Aileron 1 - Aileron 2 - Elevator - Rudder - Throttle - - - - - VTOL - Roman Bapst <roman@px4.io> - VTOL Quad Tailsitter - - - VTOL - Roman Bapst <roman@px4.io> - VTOL Quad Tailsitter - motor 1 - motor 2 - motor 4 - motor 5 - elevon left - elevon right - canard surface - rudder + VTOL Tailsitter - - VTOL - Roman Bapst <roman@uaventure.com> - VTOL Tiltrotor - Front right motor bottom - Front right motor top - Back motor bottom - Back motor top - Front left motor bottom - Front left motor top - Tilt servo - Elevon 1 - Elevon 2 - Gear - - - VTOL - Samay Siga <samay_s@icloud.com> - VTOL Tiltrotor - - + VTOL - Andreas Antener <andreas@uaventure.com> + VTOL Tiltrotor - Motor right - Motor left - Motor back - empty - Tilt servo right - Tilt servo left - Elevon right - Elevon left - + VTOL - VTOL Tiltrotor - motor 1 - motor 2 - motor 3 - motor 4 - Motor tilt front left - Motor tilt front right - Motor tilt rear left - Motor tilt rear right - Aileron left - Aileron right - Elevator - Rudder diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 5a80440dbc9..bf9c8911402 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -196,6 +196,165 @@ us + + + First 4 characters of CALLSIGN + Sets first 4 characters of a total of 8. Valid characters are A-Z, 0-9, " ". Example "PX4 " -> 1347957792 For CALLSIGN shorter than 8 characters use the null terminator at the end '\0'. + true + + + Second 4 characters of CALLSIGN + Sets second 4 characters of a total of 8. Valid characters are A-Z, 0-9, " " only. Example "TEST" -> 1413829460 For CALLSIGN shorter than 8 characters use the null terminator at the end '\0'. + true + + + ADSB-Out Emergency State + Sets the vehicle emergency state + 0 + 6 + false + + NoEmergency + General + Medical + LowFuel + NoCommunications + Interference + Downed + + + + ADSB-Out Vehicle Emitter Type + Configure the emitter type of the vehicle. + 0 + 15 + true + + Unknown + Light + Small + Large + HighVortex + Heavy + Performance + Rotorcraft + RESERVED + Glider + LightAir + Parachute + UltraLight + RESERVED + UAV + Space + RESERVED + EmergencySurf + ServiceSurf + PointObstacle + + + + ADSB-Out GPS Offset lat + Sets GPS lataral offset encoding + 0 + 7 + false + + NoData + LatLeft2M + LatLeft4M + LatLeft6M + LatRight0M + LatRight2M + LatRight4M + LatRight6M + + + + ADSB-Out GPS Offset lon + Sets GPS longitudinal offset encoding + 0 + 1 + false + + NoData + AppliedBySensor + + + + ADSB-Out ICAO configuration + Defines the ICAO ID of the vehicle + -1 + 16777215 + true + + + ADSB-In Special ICAO configuration + This vehicle is always tracked. Use 0 to disable. + 0 + 16777215 + false + + + ADSB-Out Ident Configuration + Enable Identification of Position feature + false + + + ADSB-Out Vehicle Size Configuration + Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size. + 0 + 15 + true + + SizeUnknown + Len15_Wid23 + Len25_Wid28 + Len25_Wid34 + Len35_Wid33 + Len35_Wid38 + Len45_Wid39 + Len45_Wid45 + Len55_Wid45 + Len55_Wid52 + Len65_Wid59 + Len65_Wid67 + Len75_Wid72 + Len75_Wid80 + Len85_Wid80 + Len85_Wid90 + + + + ADSB-In Vehicle List Size + Change number of targets to track + 0 + 50 + true + + + ADSB-Out Vehicle Max Speed + Informs ADSB vehicles of this vehicle's max speed capability + 0 + 6 + true + + UnknownMaxSpeed + 75Kts + 150Kts + 300Kts + 600Kts + 1200Kts + Over1200Kts + + + + ADSB-Out squawk code configuration + This parameter defines the squawk code. Value should be between 0000 and 7777. + 0 + 7777 + false + + Airspeed Selector: Gate size for sideslip angle fusion @@ -210,10 +369,19 @@ 0 1 rad + 3 - + Enable checks on airspeed sensors - If set to true then the data comming from the airspeed sensors is checked for validity. Only applied if ASPD_PRIMARY > 0. + Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0. Note that the data missing check is enabled if any of the options is set. + 0 + 15 + + Only data missing check (triggers if more than 1s no data) + Data stuck (triggers if data is exactly constant for 2s in FW mode) + Innovation check (see ASPD_FS_INNOV) + Load factor check (triggers if measurement is below stall speed) + Enable fallback to sensor-less airspeed estimation @@ -223,17 +391,21 @@ Enable fallback to sensor-less estimation - - Airspeed failsafe consistency threshold - This specifies the minimum airspeed test ratio required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Start with a value of 1.0 when tuning. When tas_test_ratio is > 1.0 it indicates the inconsistency between predicted and measured airspeed is large enough to cause the wind EKF to reject airspeed measurements. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter. + + Airspeed failure innovation threshold + This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed) and measured airspeed. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter. 0.5 - 3.0 + 10.0 + m/s + 1 - - Airspeed failsafe consistency delay - This sets the time integral of airspeed test ratio exceedance above ASPD_FS_INNOV required to trigger a failsafe. For example if ASPD_FS_INNOV is 1 and estimator_status.tas_test_ratio is 2.0, then the exceedance is 1.0 and the integral will rise at a rate of 1.0/second. A negative value disables the check. Larger positive values make the check less sensitive, smaller positive values make it more sensitive. - 30.0 - s + + Airspeed failure innovation integral threshold + This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe. Larger values make the check less sensitive, smaller positive values make it more sensitive. + 0.0 + 50.0 + m + 1 Airspeed failsafe start delay @@ -260,22 +432,45 @@ Third airspeed sensor - - Airspeed scale (scale from IAS to CAS) - Scale can either be entered manually, or estimated in-flight by setting ASPD_SCALE_EST to 1. + + Scale of airspeed sensor 1 + This is the scale IAS --> CAS of the first airspeed sensor instance 0.5 - 1.5 + 2.0 + 2 + true + + + Scale of airspeed sensor 2 + This is the scale IAS --> CAS of the second airspeed sensor instance + 0.5 + 2.0 + 2 + true + + + Scale of airspeed sensor 3 + This is the scale IAS --> CAS of the third airspeed sensor instance + 0.5 + 2.0 + 2 + true - - Automatic airspeed scale estimation on - Turns the automatic airspeed scale (scale from IAS to CAS) on or off. It is recommended to fly level altitude while performing the estimation. Set to 1 to start estimation (best when already flying). Set to 0 to end scale estimation. The estimated scale is then saved using the ASPD_SCALE parameter. + + Controls when to apply the new estimated airspeed scale(s) + + Do not automatically apply the estimated scale + Apply the estimated scale after disarm + Apply the estimated scale in air + - - Airspeed Selector: Wind estimator true airspeed scale process noise - Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. + + Airspeed Selector: Wind estimator true airspeed scale process noise spectral density + Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second. 0 0.1 - Hz + 1/s/sqrt(Hz) + 5 Airspeed Selector: Gate size for true airspeed fusion @@ -290,164 +485,27 @@ 0 4 m/s + 1 - - Airspeed Selector: Wind estimator wind process noise - Wind process noise of the internal wind estimator(s) of the airspeed selector. - 0 - 1 - m/s^2 - - - - - Body X axis angular velocity D gain - Body X axis angular velocity differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - 0.0 - 2.0 - 4 - 0.01 - - - Body X axis angular velocity feedforward gain - Improves tracking performance. - 0.0 - Nm/(rad/s) - 4 - - - Body X axis angular velocity I gain - Body X axis angular velocity integral gain. Can be set to compensate static thrust difference or gravity center offset. - 0.0 - Nm/rad - 3 - 0.01 - - - Body X axis angular velocity integrator limit - Body X axis angular velocity integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes. - 0.0 - Nm - 2 - 0.01 - - - Body X axis angular velocity controller gain - Global gain of the controller. This gain scales the P, I and D terms of the controller: output = AVC_X_K * (AVC_X_P * error + AVC_X_I * error_integral + AVC_X_D * error_derivative) Set AVC_X_P=1 to implement a PID in the ideal form. Set AVC_X_K=1 to implement a PID in the parallel form. - 0.0 - 5.0 - 4 - 0.0005 - - - Body X axis angular velocity P gain - Body X axis angular velocity proportional gain, i.e. control output for angular speed error 1 rad/s. - 0.0 - 20.0 - 1/s - 3 - 0.01 - - - Body Y axis angular velocity D gain - Body Y axis angular velocity differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - 0.0 - 2.0 - 4 - 0.01 - - - Body Y axis angular velocity feedforward - Improves tracking performance. - 0.0 - Nm/(rad/s) - 4 - - - Body Y axis angular velocity I gain - Body Y axis angular velocity integral gain. Can be set to compensate static thrust difference or gravity center offset. - 0.0 - Nm/rad - 3 - 0.01 - - - Body Y axis angular velocity integrator limit - Body Y axis angular velocity integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes. - 0.0 - Nm - 2 - 0.01 - - - Body Y axis angular velocity controller gain - Global gain of the controller. This gain scales the P, I and D terms of the controller: output = AVC_Y_K * (AVC_Y_P * error + AVC_Y_I * error_integral + AVC_Y_D * error_derivative) Set AVC_Y_P=1 to implement a PID in the ideal form. Set AVC_Y_K=1 to implement a PID in the parallel form. - 0.0 - 20.0 - 4 - 0.0005 - - - Body Y axis angular velocity P gain - Body Y axis angular velocity proportional gain, i.e. control output for angular speed error 1 rad/s. - 0.0 - 20.0 - 1/s + + Horizontal wind uncertainty threshold for synthetic airspeed + The synthetic airspeed estimate (from groundspeed and heading) will be declared valid as soon and as long the horizontal wind uncertainty drops below this value. + 0.001 + 5 + m/s 3 - 0.01 - - - Body Z axis angular velocity D gain - Body Z axis angular velocity differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - 0.0 - 2.0 - 2 - 0.01 - - - Body Z axis angular velocity feedforward - Improves tracking performance. - 0.0 - Nm/(rad/s) - 4 - 0.01 - - - Body Z axis angular velocity I gain - Body Z axis angular velocity integral gain. Can be set to compensate static thrust difference or gravity center offset. - 0.0 - Nm/rad - 2 - 0.01 - - - Body Z axis angular velocity integrator limit - Body Z axis angular velocity integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes. - 0.0 - Nm - 2 - 0.01 - - - Body Z axis angular velocity controller gain - Global gain of the controller. This gain scales the P, I and D terms of the controller: output = AVC_Z_K * (AVC_Z_P * error + AVC_Z_I * error_integral + AVC_Z_D * error_derivative) Set AVC_Z_P=1 to implement a PID in the ideal form. Set AVC_Z_K=1 to implement a PID in the parallel form. - 0.0 - 5.0 - 4 - 0.0005 - - Body Z axis angular velocity P gain - Body Z axis angular velocity proportional gain, i.e. control output for angular speed error 1 rad/s. - 0.0 - 20.0 - 1/s + + Airspeed Selector: Wind estimator wind process noise noise spectral density + Wind process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. + 0 + 1 + m/s^2/sqrt(Hz) 2 - 0.01 - + Acceleration compensation based on GPS velocity @@ -502,212 +560,95 @@ 2 - - - Battery 1 current per volt (A/V) - The voltage seen by the ADC multiplied by this factor will determine the battery current. A value of -1 means to use the board default. - 8 - True - - - Battery 1 capacity - Defines the capacity of battery 1 in mAh. - -1.0 - 100000 - mAh - 0 - 50 - True - - - Battery 1 Current ADC Channel - This parameter specifies the ADC channel used to monitor current of main power battery. A value of -1 means to use the board default. - True - - - Number of cells for battery 1 - Defines the number of cells the attached battery consists of. - True - - 2S Battery - 3S Battery - 4S Battery - 5S Battery - 6S Battery - 7S Battery - 8S Battery - 9S Battery - 10S Battery - 11S Battery - 12S Battery - 13S Battery - 14S Battery - 15S Battery - 16S Battery - - - - Explicitly defines the per cell internal resistance for battery 1 - If non-negative, then this will be used in place of BAT1_V_LOAD_DROP for all calculations. - -1.0 - 0.2 - Ohm - 2 - 0.01 - True - - - Battery 1 monitoring source - This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current. - True + + + Controls when to apply the new gains + After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. - Disabled - Power Module - External - ESCs + Do not apply the new gains (logging only) + Apply the new gains after disarm + Apply the new gains in air - - Battery 1 Voltage ADC Channel - This parameter specifies the ADC channel used to monitor voltage of main power battery. A value of -1 means to use the board default. - True - - - Full cell voltage (5C load) - Defines the voltage where a single cell of battery 1 is considered full under a mild load. This will never be the nominal voltage of 4.2V - V - 2 - 0.01 - True - - - Battery 1 voltage divider (V divider) - This is the divider from battery 1 voltage to ADC voltage. If using e.g. Mauch power modules the value from the datasheet can be applied straight here. A value of -1 means to use the board default. - 8 - True - - - Empty cell voltage (5C load) - Defines the voltage where a single cell of battery 1 is considered empty. The voltage should be chosen before the steep dropoff to 2.8V. A typical lithium battery can only be discharged down to 10% before it drops off to a voltage level damaging the cells. - V - 2 - 0.01 - True + + Tuning axes selection + Defines which axes will be tuned during the auto-tuning sequence Set bits in the following positions to enable: 0 : Roll 1 : Pitch 2 : Yaw + 1 + 7 + + roll + pitch + yaw + - - Voltage drop per cell on full throttle - This implicitely defines the internal resistance to maximum current ratio for battery 1 and assumes linearity. A good value to use is the difference between the 5C and 20-25C load. Not used if BAT1_R_INTERNAL is set. - 0.07 - 0.5 - V - 2 - 0.01 - True + + Enable/disable auto tuning using an RC AUX input + Defines which RC_MAP_AUXn parameter maps the RC channel used to enable/disable auto tuning. + 0 + 6 + + Disable + Aux1 + Aux2 + Aux3 + Aux4 + Aux5 + Aux6 + - - Battery 2 current per volt (A/V) - The voltage seen by the ADC multiplied by this factor will determine the battery current. A value of -1 means to use the board default. - 8 - True + + Start the autotuning sequence + WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using FW_AT_SYSID_AMP for more signal/noise ratio - - Battery 2 capacity - Defines the capacity of battery 2 in mAh. - -1.0 - 100000 - mAh - 0 - 50 - True - - - Battery 2 Current ADC Channel - This parameter specifies the ADC channel used to monitor current of main power battery. A value of -1 means to use the board default. - True - - - Number of cells for battery 2 - Defines the number of cells the attached battery consists of. - True - - 2S Battery - 3S Battery - 4S Battery - 5S Battery - 6S Battery - 7S Battery - 8S Battery - 9S Battery - 10S Battery - 11S Battery - 12S Battery - 13S Battery - 14S Battery - 15S Battery - 16S Battery - - - - Explicitly defines the per cell internal resistance for battery 2 - If non-negative, then this will be used in place of BAT2_V_LOAD_DROP for all calculations. - -1.0 - 0.2 - Ohm - 2 - 0.01 - True + + Amplitude of the injected signal + This parameter scales the signal sent to the rate controller during system identification. + 0.1 + 6.0 + 1 - - Battery 2 monitoring source - This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current. - True + + Controls when to apply the new gains + After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. WARNING Applying the gains in air is dangerous as there is no guarantee that those new gains will be able to stabilize the drone properly. - Disabled - Power Module - External - ESCs + Do not apply the new gains (logging only) + Apply the new gains after disarm + WARNING Apply the new gains in air - - Battery 2 Voltage ADC Channel - This parameter specifies the ADC channel used to monitor voltage of main power battery. A value of -1 means to use the board default. - True + + Multicopter autotune module enable - - Full cell voltage (5C load) - Defines the voltage where a single cell of battery 1 is considered full under a mild load. This will never be the nominal voltage of 4.2V - V + + Desired angular rate closed-loop rise time + 0.01 + 0.5 + s 2 - 0.01 - True - - - Battery 2 voltage divider (V divider) - This is the divider from battery 2 voltage to ADC voltage. If using e.g. Mauch power modules the value from the datasheet can be applied straight here. A value of -1 means to use the board default. - 8 - True - - Empty cell voltage (5C load) - Defines the voltage where a single cell of battery 1 is considered empty. The voltage should be chosen before the steep dropoff to 2.8V. A typical lithium battery can only be discharged down to 10% before it drops off to a voltage level damaging the cells. - V - 2 - 0.01 - True + + Start the autotuning sequence + WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using MC_AT_SYSID_AMP for more signal/noise ratio - - Voltage drop per cell on full throttle - This implicitely defines the internal resistance to maximum current ratio for battery 1 and assumes linearity. A good value to use is the difference between the 5C and 20-25C load. Not used if BAT2_R_INTERNAL is set. - 0.07 - 0.5 - V - 2 - 0.01 - True + + Amplitude of the injected signal + 0.1 + 6.0 + 1 + + This parameter is deprecated. Please use BAT1_I_CHANNEL + + Expected battery current in flight + This value is used to initialize the in-flight average current estimation, which in turn is used for estimating remaining flight time and RTL triggering. + 0 + 500 + A + 0.1 + Critical threshold Sets the threshold when the battery will be reported as critically low. This has to be lower than the low threshold. This threshold commonly will trigger RTL. @@ -741,7 +682,7 @@ This parameter is deprecated. Please use BAT1_V_CHARGED instead - + This parameter is deprecated. Please use BAT1_V_EMPTY instead @@ -849,22 +790,6 @@ Distance based, on command (Survey mode) - - Camera trigger pin - Selects which FMU pin is used (range: AUX1-AUX8 on Pixhawk controllers with an I/O board, MAIN1-MAIN8 on controllers without an I/O board). The PWM interface takes two pins per camera, while relay triggers on every pin individually. Example: Value 56 would trigger on pins 5 and 6. For GPIO mode Pin 6 will be triggered followed by 5. With a value of 65 pin 5 will be triggered followed by 6. Pins may be non contiguous. I.E. 16 or 61. In GPIO mode the delay pin to pin is < .2 uS. - 1 - 12345678 - 0 - true - - - Camera trigger pin extended - This Bit mask selects which FMU pin is used (range: AUX9-AUX32) If the value is not 0 it takes precedence over TRIG_PINS. If bits above 8 are set that value is used as the selector for trigger pins. greater then 8. 0x00000300 Would be Pins 9,10. If the value is - 0 - 2147483647 - 0 - true - Camera trigger polarity This parameter sets the polarity of the trigger (0 = active low, 1 = active high ) @@ -906,13 +831,6 @@ 782097 true - - Circuit breaker for engine failure detection - Setting this parameter to 284953 will disable the engine failure detection. If the aircraft is in engine failure mode the engine failure flag will be set to healthy WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK - 0 - 284953 - true - Circuit breaker for flight termination Setting this parameter to 121212 will disable the flight termination action if triggered by the FailureDetector logic or if FMU is lost. This circuit breaker does not affect the RC loss, data link loss, geofence, and takeoff failure detection safety logic. @@ -926,13 +844,6 @@ 0 22027 - - Circuit breaker for rate controller output - Setting this parameter to 140253 will disable the rate controller uORB publication. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK - 0 - 140253 - true - Circuit breaker for power supply check Setting this parameter to 894281 will disable the power valid checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK @@ -945,12 +856,6 @@ 0 197848 - - Circuit breaker for position error check - Setting this parameter to 201607 will disable the position and velocity accuracy checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK - 0 - 201607 - Circuit breaker for arming in fixed-wing mode check Setting this parameter to 159753 will enable arming in fixed-wing mode for VTOLs. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK @@ -959,12 +864,25 @@ - - Enable preflight check for maximal allowed airspeed when arming - Deny arming if the current airspeed measurement is greater than half the cruise airspeed (FW_AIRSPD_TRIM). Excessive airspeed measurements on ground are either caused by wind or bad airspeed calibration. + + Set the actuator failure failsafe mode + Note: actuator failure needs to be enabled and configured via FD_ACT_* parameters. + 0 + 3 - Disabled - Enabled + Warning only + Hold mode + Land mode + Return mode + Terminate + + + + Flag to allow arming + Set 0 to prevent accidental use of the vehicle e.g. for safety or maintenance reasons. + + Disallow arming + Allow arming @@ -1022,6 +940,10 @@ 2 0.05 + + Enable FMU SD card hardfault detection check + This check detects if there are hardfault files present on the SD card. If so, and the parameter is enabled, arming is prevented. + Maximum accelerometer inconsistency between IMU units that will allow arming 0.1 @@ -1038,21 +960,35 @@ 3 0.01 - + Maximum magnetic field inconsistency between units that will allow arming Set -1 to disable the check. 3 180 deg - + Enable mag strength preflight check - Deny arming if the estimator detects a strong magnetic disturbance (check enabled by EKF2_MAG_CHECK) + Check if the estimator detects a strong magnetic disturbance (check enabled by EKF2_MAG_CHECK) + + Disabled + Deny arming + Warning only + Require valid mission to arm The default allows to arm the vehicle without a valid mission. + + Enable Drone ID system detection and health check + This check detects if the Open Drone ID system is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming. + + Disabled + Warning only + Enforce Open Drone ID system presence + + Enable FMU SD card detection check This check detects if the FMU SD card is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming. @@ -1068,13 +1004,12 @@ Allow arming without GPS - The default allows the vehicle to arm without GPS signal. Require GPS lock to arm Allow arming without GPS - + Maximum allowed CPU load to still arm A negative value disables the check. -1 @@ -1086,49 +1021,32 @@ Time-out for auto disarm after landing A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. A zero or negative value means that automatic disarming triggered by landing detection is disabled. s - 2 + 1 + 0.1 Time-out for auto disarm if not taking off A non-zero, positive value specifies the time in seconds, within which the vehicle is expected to take off after arming. In case the vehicle didn't takeoff within the timeout it disarms again. A negative value disables autmoatic disarming triggered by a pre-takeoff timeout. s - 2 + 1 + 0.1 - Datalink loss time threshold - After this amount of seconds without datalink the data link lost mode triggers + GCS connection loss time threshold + After this amount of seconds without datalink, the GCS connection lost mode triggers 5 300 s 1 1 - - Engine Failure Current/Throttle Threshold - Engine failure triggers only below this current value - 0.0 - 50.0 - A/% - 2 - 1 - - - Engine Failure Throttle Threshold - Engine failure triggers only above this throttle value + + Delay between failsafe condition triggered and failsafe reaction + Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode for the user to realize. During that time the user cannot take over control via the stick override feature see COM_RC_OVERRIDE. Afterwards the configured failsafe action is triggered and the user may use stick override. A zero value disables the delay and the user cannot take over via stick movements (switching modes is still allowed). 0.0 - 1.0 - norm - 2 - 0.01 - - - Engine Failure Time Threshold - Engine failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time - 0.0 - 60.0 + 25.0 s - 1 - 1 + 3 Next flight UUID @@ -1152,6 +1070,7 @@ Takeoff Land Follow Me + Precision Land @@ -1171,6 +1090,7 @@ Takeoff Land Follow Me + Precision Land @@ -1190,6 +1110,7 @@ Takeoff Land Follow Me + Precision Land @@ -1209,6 +1130,7 @@ Takeoff Land Follow Me + Precision Land @@ -1228,6 +1150,7 @@ Takeoff Land Follow Me + Precision Land @@ -1247,6 +1170,7 @@ Takeoff Land Follow Me + Precision Land @@ -1259,6 +1183,16 @@ Developer + + Maximum allowed flight time + The vehicle aborts the current operation and returns to launch when the time since takeoff is above this value. It is not possible to resume the mission or switch to any auto mode other than RTL or Land. Taking over in any manual mode is still possible. Starting from 90% of the maximum flight time, a warning message will be sent every 1 minute with the remaining time until automatic RTL. Set to -1 to disable. + -1 + s + + + Enable force safety + Force safety when the vehicle disarms + High Latency Datalink loss time threshold After this amount of seconds without datalink the data link lost mode triggers @@ -1273,27 +1207,25 @@ 60 s - - Home set horizontal threshold - The home position will be set if the estimated positioning accuracy is below the threshold. - 2 - 15 - m - 2 - 0.5 + + Home position enabled + Set home position automatically if possible. + true Allows setting the home position after takeoff If set to true, the autopilot is allowed to set its home position after takeoff The true home position is back-computed if a local position is estimate if available. If no local position is available, home is set to the current position. - - Home set vertical threshold - The home position will be set if the estimated positioning accuracy is below the threshold. - 5 - 25 - m - 2 - 0.5 + + Imbalanced propeller failsafe mode + Action the system takes when an imbalanced propeller is detected by the failure detector. See also FD_IMB_PROP_THR to set the failure threshold. + 1 + + Disabled + Warning + Return + Land + Timeout value for disarming when kill switch is engaged @@ -1304,7 +1236,7 @@ Timeout for detecting a failure after takeoff - A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to put the vehicle into a lockdown state if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW). A zero or negative value means that the check is disabled. + A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to disarm the vehicle if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW). A zero or negative value means that the check is disabled. -1.0 5.0 s @@ -1313,8 +1245,6 @@ Battery failsafe mode Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR for definition of battery states. - 0 - 1 Warning Land mode @@ -1322,8 +1252,8 @@ - Enable Motor Testing - If set, enables the motor test interface via MAVLink (DO_MOTOR_TEST), that allows spinning the motors for testing purposes. + Enable Actuator Testing + If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that allows spinning the motors and moving the servos for testing purposes. Time-out to wait when onboard computer connection is lost before warning about loss connection @@ -1332,23 +1262,10 @@ s 0.01 - - Set offboard loss failsafe mode - The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. - - Disabled - Land mode - Hold mode - Return mode - Terminate - Lockdown - - - Set offboard loss failsafe mode when RC is available + Set offboard loss failsafe mode The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. - Disabled Position mode Altitude mode Manual @@ -1356,7 +1273,7 @@ Land mode Hold mode Terminate - Lockdown + Disarm @@ -1364,18 +1281,21 @@ Time-out to wait when offboard connection is lost before triggering offboard lost action - See COM_OBL_ACT and COM_OBL_RC_ACT to configure action. + See COM_OBL_RC_ACT to configure action. 0 60 s 0.01 + + Expect and require a healthy MAVLink parachute system + Position control navigation loss response - This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control. Navigation accuracy checks can be disabled using the CBRK_VELPOSERR parameter, but doing so will remove protection for all flight modes. + This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control. If Altitude/Manual is selected: assume use of remote control after fallback. Switch to Altitude mode if a height estimate is available, else switch to MANUAL. If Land/Descend is selected: assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to Descend. - Altitude/Manual. Assume use of remote control after fallback. Switch to Altitude mode if a height estimate is available, else switch to MANUAL. - Land/Terminate. Assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to TERMINATION. + Altitude/Manual + Land/Descend @@ -1385,28 +1305,21 @@ 100 s - + Horizontal position error threshold - This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. + This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous position error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). Set to -1 to disable. + -1 + 400 m + 1 - - Vertical position error threshold - This is the vertical position error (EPV) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. + + EPH threshold for RTL + Specify the threshold for triggering a warning for low local position accuracy. Additionally triggers a RTL if currently in Mission or Loiter mode. Local position has to be still declared valid, which is most of all depending on COM_POS_FS_EPH. Use this feature on systems with dead-reckoning capabilites (e.g. fixed-wing vehicles with airspeed sensor) to improve the user notification and failure mitigation when flying in GNSS-denied areas. Set to -1 to disable. + -1 + 1000 m - - Loss of position probation gain factor - This sets the rate that the loss of position probation time grows when position checks are failing. The default value has been optimised for rotary wing applications. For fixed wing applications a value of 0 should be used. - true - - - Loss of position probation delay at takeoff - The probation delay is the number of seconds that the EKF innovation checks need to pass for the position to be declared good after it has been declared bad. The probation delay will be reset to this parameter value when takeoff is detected. After takeoff, if position checks are passing, the probation delay will reduce by one second for every lapsed second of valid position down to a minimum of 1 second. If position checks are failing, the probation delay will increase by COM_POS_FS_GAIN seconds for every lapsed second up to a maximum of 100 seconds. The default value has been optimised for rotary wing applications. For fixed wing applications, a value of 1 should be used. - 1 - 100 - s - Required number of redundant power modules This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected. Note: CBRK_SUPPLY_CHK disables all power checks including this one. @@ -1422,13 +1335,14 @@ Always - - Delay between RC loss and configured reaction - RC signal not updated -> still use data for COM_RC_LOSS_T seconds Consider RC signal lost -> wait COM_RCL_ACT_T seconds on the spot waiting to regain signal React with failsafe action NAV_RCL_ACT A zero value disables the delay. - 0.0 - 25.0 - s - 3 + + Set command after a quadchute + + Warning only + Return mode + Land mode + Hold mode + RC loss exceptions @@ -1448,15 +1362,17 @@ 1500 ms - + RC control input mode - The default value of 0 requires a valid RC transmitter setup. Setting this to 1 allows joystick control and disables RC input handling and the associated checks. A value of 2 will generate RC control data from manual input received via MAVLink instead of directly forwarding the manual input data. + A value of 0 enables RC transmitter control (only). A valid RC transmitter calibration is required. A value of 1 allows joystick control only. RC input handling and the associated checks are disabled. A value of 2 allows either RC Transmitter or Joystick input. The first valid input is used, will fallback to other sources if the input stream becomes invalid. A value of 3 allows either input from RC or joystick. The first available source is selected and used until reboot. A value of 4 ignores any stick input. 0 - 2 + 4 - RC Transmitter - Joystick/No RC Checks - Virtual RC by Joystick + RC Transmitter only + Joystick only + RC and Joystick with fallback + RC or Joystick keep first + Stick input disabled @@ -1470,13 +1386,12 @@ Enable RC stick override of auto and/or offboard modes - When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV from their center position immediately gives control back to the pilot by switching to Position mode. Note: Only has an effect on multicopters, and VTOLs in multicopter mode. + When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV immediately gives control back to the pilot by switching to Position mode and if position is unavailable Altitude mode. Note: Only has an effect on multicopters, and VTOLs in multicopter mode. 0 - 7 + 3 Enable override during auto modes (except for in critical battery reaction) Enable override during offboard mode - Ignore throttle stick @@ -1488,9 +1403,14 @@ 0 0.05 - - Rearming grace period - Re-arming grace allows to rearm the drone with manual command without running prearmcheck during 5 s after disarming. + + Enforced delay between arming and further navigation + The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds. Goal: - Motors and propellers spool up to idle speed before getting commanded to spin faster - Timeout for ESCs and smart batteries to successfulyy do failure checks e.g. for stuck rotors before the vehicle is off the ground + 0 + 30 + s + 1 + 0.1 Action after TAKEOFF has been accepted @@ -1500,14 +1420,32 @@ Mission (if valid) - + Horizontal velocity error threshold - This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. + This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous velocity error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). + 0 + m/s + 1 + + + Wind speed RTL threshold + Wind speed threshold above which an automatic return to launch is triggered. It is not possible to resume the mission or switch to any auto mode other than RTL or Land if this threshold is exceeded. Taking over in any manual mode is still possible. Set to -1 to disable. + -1 + m/s + 1 + 0.1 + + + Wind speed warning threshold + A warning is triggered if the currently estimated wind speed is above this value. Warning is sent periodically (every 1 minute). Set to -1 to disable. + -1 m/s + 1 + 0.1 - Set data link loss failsafe mode - The data link loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed. + Set GCS connection loss failsafe mode + The GCS connection loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed. 0 6 @@ -1516,7 +1454,7 @@ Return mode Land mode Terminate - Lockdown + Disarm @@ -1529,531 +1467,193 @@ Return mode Land mode Terminate - Lockdown + Disarm - - Maximum allowed RTL flight in minutes - This is used to determine when the vehicle should be switched to RTL due to low battery. Note, particularly for multirotors this should reflect flight time at cruise speed, not while stationary - min - - - - Maximum value for actuator 0 - - - Minimum value for actuator 0 - - - Maximum value for actuator 10 - - - Minimum value for actuator 10 - - - Maximum value for actuator 11 - - - Minimum value for actuator 11 + + + UAVCAN/CAN v1 bus bitrate + 20000 + 1000000 + bit/s + true - - Maximum value for actuator 12 + + Cyphal + 0 - Cyphal disabled. 1 - Enables Cyphal + true - - Minimum value for actuator 12 + + Cyphal Node ID + Read the specs at http://uavcan.org to learn more about Node ID. + -1 + 125 + true - - Maximum value for actuator 13 + + actuator_outputs uORB over Cyphal publication port ID + -1 + 6143 - - Minimum value for actuator 13 + + UDRAL battery parameters subscription port ID + -1 + 6143 - - Maximum value for actuator 14 + + UDRAL battery status subscription port ID + -1 + 6143 - - Minimum value for actuator 14 + + UDRAL battery energy source subscription port ID + -1 + 6143 - - Maximum value for actuator 15 + + ESC 0 subscription port ID + -1 + 6143 - - Minimum value for actuator 15 + + Cyphal ESC publication port ID + -1 + 6143 - - Maximum value for actuator 1 + + GPS 0 subscription port ID + -1 + 6143 - - Minimum value for actuator 1 + + GPS 1 subscription port ID + -1 + 6143 - - Maximum value for actuator 2 + + Cyphal GPS publication port ID + -1 + 6143 - - Minimum value for actuator 2 + + Cyphal legacy battery port ID + -1 + 6143 - - Maximum value for actuator 3 + + Cyphal Servo publication port ID + -1 + 6143 - - Minimum value for actuator 3 + + sensor_gps uORB over Cyphal subscription port ID + -1 + 6143 - - Maximum value for actuator 4 + + sensor_gps uORB over Cyphal publication port ID + -1 + 6143 - - Minimum value for actuator 4 + + + + 1-sigma IMU accelerometer switch-on bias + 0.0 + 0.5 + m/s^2 + 2 + true - - Maximum value for actuator 5 + + Maximum IMU accel magnitude that allows IMU bias learning + If the magnitude of the IMU accelerometer vector exceeds this value, the EKF delta velocity state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the delta velocity bias estimates. + 20.0 + 200.0 + m/s^2 + 1 - - Minimum value for actuator 5 + + Maximum IMU gyro angular rate magnitude that allows IMU bias learning + If the magnitude of the IMU angular rate vector exceeds this value, the EKF delta velocity state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the delta velocity bias estimates. + 2.0 + 20.0 + rad/s + 1 - - Maximum value for actuator 6 + + Accelerometer bias learning limit + The ekf delta velocity bias states will be limited to within a range equivalent to +- of this value. + 0.0 + 0.8 + m/s^2 + 2 - - Minimum value for actuator 6 + + Time constant used by acceleration and angular rate magnitude checks used to inhibit delta velocity bias learning + The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay. + 0.1 + 1.0 + s + 2 - - Maximum value for actuator 7 + + Process noise for IMU accelerometer bias prediction + 0.0 + 0.01 + m/s^3 + 6 - - Minimum value for actuator 7 + + Accelerometer noise for covariance prediction + 0.01 + 1.0 + m/s^2 + 2 - - Maximum value for actuator 8 + + Will be removed after v1.14 release + Set bits in the following positions to enable: 0 : Deprecated, use EKF2_GPS_CTRL instead 1 : Deprecated. use EKF2_OF_CTRL instead 2 : Deprecated, use EKF2_IMU_CTRL instead 3 : Deprecated, use EKF2_EV_CTRL instead 4 : Deprecated, use EKF2_EV_CTRL instead 5 : Deprecated. use EKF2_DRAG_CTRL instead 6 : Deprecated, use EKF2_EV_CTRL instead 7 : Deprecated, use EKF2_GPS_CTRL instead 8 : Deprecated, use EKF2_EV_CTRL instead + 0 + 511 + true + + unused + unused + unused + unused + unused + unused + unused + unused + unused + - - Minimum value for actuator 8 + + 1-sigma tilt angle uncertainty after gravity vector alignment + 0.0 + 0.5 + rad + 3 + true - - Maximum value for actuator 9 + + Airspeed fusion threshold + A value of zero will deactivate airspeed fusion. Any other positive value will determine the minimum airspeed which will still be fused. Set to about 90% of the vehicles stall speed. Both airspeed fusion and sideslip fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_FUSE_BETA to activate sideslip fusion. Note: side slip fusion is currently not supported for tailsitters. + 0.0 + m/s + 1 - - Minimum value for actuator 9 + + Upper limit on airspeed along individual axes used to correct baro for position error effects + 5.0 + 50.0 + m/s + 1 - - Airframe ID - This is used to retrieve pre-computed control effectiveness matrix - 0 - 2 - - Multirotor - Standard VTOL (WIP) - Tiltrotor VTOL (WIP) - - - - Airspeed scaler - This compensates for the variation of flap effectiveness with airspeed. - - - Battery power level scaler - This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery. - - - Axis of rotor 0 thrust vector, X body axis component - - - Axis of rotor 0 thrust vector, Y body axis component - - - Axis of rotor 0 thrust vector, Z body axis component - - - Thrust coefficient of rotor 0 - The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT0_MIN and CA_ACT0_MAX) is the output signal sent to the motor controller. - - - Moment coefficient of rotor 0 - The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. - - - Position of rotor 0 along X body axis - - - Position of rotor 0 along Y body axis - - - Position of rotor 0 along Z body axis - - - Axis of rotor 1 thrust vector, X body axis component - - - Axis of rotor 1 thrust vector, Y body axis component - - - Axis of rotor 1 thrust vector, Z body axis component - - - Thrust coefficient of rotor 1 - The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT1_MIN and CA_ACT1_MAX) is the output signal sent to the motor controller. - - - Moment coefficient of rotor 1 - The moment coefficient if defined as Torque = KM * Thrust, Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. - - - Position of rotor 1 along X body axis - - - Position of rotor 1 along Y body axis - - - Position of rotor 1 along Z body axis - - - Axis of rotor 2 thrust vector, X body axis component - - - Axis of rotor 2 thrust vector, Y body axis component - - - Axis of rotor 2 thrust vector, Z body axis component - - - Thrust coefficient of rotor 2 - The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT2_MIN and CA_ACT2_MAX) is the output signal sent to the motor controller. - - - Moment coefficient of rotor 2 - The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. - - - Position of rotor 2 along X body axis - - - Position of rotor 2 along Y body axis - - - Position of rotor 2 along Z body axis - - - Axis of rotor 3 thrust vector, X body axis component - - - Axis of rotor 3 thrust vector, Y body axis component - - - Axis of rotor 3 thrust vector, Z body axis component - - - Thrust coefficient of rotor 3 - The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT3_MIN and CA_ACT3_MAX) is the output signal sent to the motor controller. - - - Moment coefficient of rotor 3 - The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. - - - Position of rotor 3 along X body axis - - - Position of rotor 3 along Y body axis - - - Position of rotor 3 along Z body axis - - - Axis of rotor 4 thrust vector, X body axis component - - - Axis of rotor 4 thrust vector, Y body axis component - - - Axis of rotor 4 thrust vector, Z body axis component - - - Thrust coefficient of rotor 4 - The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT4_MIN and CA_ACT4_MAX) is the output signal sent to the motor controller. - - - Moment coefficient of rotor 4 - The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. - - - Position of rotor 4 along X body axis - - - Position of rotor 4 along Y body axis - - - Position of rotor 4 along Z body axis - - - Axis of rotor 5 thrust vector, X body axis component - - - Axis of rotor 5 thrust vector, Y body axis component - - - Axis of rotor 5 thrust vector, Z body axis component - - - Thrust coefficient of rotor 5 - The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT5_MIN and CA_ACT5_MAX) is the output signal sent to the motor controller. - - - Moment coefficient of rotor 5 - The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. - - - Position of rotor 5 along X body axis - - - Position of rotor 5 along Y body axis - - - Position of rotor 5 along Z body axis - - - Axis of rotor 6 thrust vector, X body axis component - - - Axis of rotor 6 thrust vector, Y body axis component - - - Axis of rotor 6 thrust vector, Z body axis component - - - Thrust coefficient of rotor 6 - The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT6_MIN and CA_ACT6_MAX) is the output signal sent to the motor controller. - - - Moment coefficient of rotor 6 - The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. - - - Position of rotor 6 along X body axis - - - Position of rotor 6 along Y body axis - - - Position of rotor 6 along Z body axis - - - Axis of rotor 7 thrust vector, X body axis component - - - Axis of rotor 7 thrust vector, Y body axis component - - - Axis of rotor 7 thrust vector, Z body axis component - - - Thrust coefficient of rotor 7 - The thrust coefficient if defined as Thrust = CT * u^2, where u (with value between CA_ACT7_MIN and CA_ACT7_MAX) is the output signal sent to the motor controller. - - - Moment coefficient of rotor 7 - The moment coefficient if defined as Torque = KM * Thrust Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. - - - Position of rotor 7 along X body axis - - - Position of rotor 7 along Y body axis - - - Position of rotor 7 along Z body axis - - - Control allocation method - 0 - 1 - - Pseudo-inverse with output clipping (default) - Pseudo-inverse with sequential desaturation technique - - - - - - DSHOT 3D deadband high - When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin. This value is with respect to the mixer_module range (0-1999), not the DSHOT values. - 1000 - 1999 - - - DSHOT 3D deadband low - When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin. This value is with respect to the mixer_module range (0-1999), not the DSHOT values. - 0 - 1000 - - - Allows for 3d mode when using DShot and suitable mixer - WARNING: ESC must be configured for 3D mode, and DSHOT_MIN set to 0. This splits the throttle ranges in two. Direction 1) 48 is the slowest, 1047 is the fastest. Direction 2) 1049 is the slowest, 2047 is the fastest. When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent. - - - Configure DShot - This enables/disables DShot. The different modes define different speeds, for example DShot150 = 150kb/s. Not all ESCs support all modes. Note: this enables DShot on the FMU outputs. For boards with an IO it is the AUX outputs. - True - - Disable (use PWM/Oneshot) - DShot150 - DShot300 - DShot600 - DShot1200 - - - - Minimum DShot Motor Output - Minimum Output Value for DShot in percent. The value depends on the ESC. Make sure to set this high enough so that the motors are always spinning while armed. - 0 - 1 - % - 2 - 0.01 - - - Serial Configuration for DShot Driver - Configure on which serial port to run DShot Driver. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - - - Number of magnetic poles of the motors - Specify the number of magnetic poles of the motors. It is required to compute the RPM value from the eRPM returned with the ESC telemetry. Either get the number from the motor spec sheet or count the magnets on the bell of the motor (not the stator magnets). Typical motors for 5 inch props have 14 poles. - - - - - Airfield home alt - Altitude of airfield home waypoint - -50 - m - 1 - 0.5 - - - Airfield home Lat - Latitude of airfield home waypoint - -900000000 - 900000000 - deg*1e7 - - - Airfield home Lon - Longitude of airfield home waypoint - -1800000000 - 1800000000 - deg*1e7 - - - - - 1-sigma IMU accelerometer switch-on bias - 0.0 - 0.5 - m/s^2 - 2 - true - - - Maximum IMU accel magnitude that allows IMU bias learning - If the magnitude of the IMU accelerometer vector exceeds this value, the EKF delta velocity state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the delta velocity bias estimates. - 20.0 - 200.0 - m/s^2 - 1 - - - Maximum IMU gyro angular rate magnitude that allows IMU bias learning - If the magnitude of the IMU angular rate vector exceeds this value, the EKF delta velocity state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the delta velocity bias estimates. - 2.0 - 20.0 - rad/s - 1 - - - Accelerometer bias learning limit - The ekf delta velocity bias states will be limited to within a range equivalent to +- of this value. - 0.0 - 0.8 - m/s^2 - 2 - - - Time constant used by acceleration and angular rate magnitude checks used to inhibit delta velocity bias learning - The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay. - 0.1 - 1.0 - s - 2 - - - Process noise for IMU accelerometer bias prediction - 0.0 - 0.01 - m/s^3 - 6 - - - Accelerometer noise for covariance prediction - 0.01 - 1.0 - m/s^2 - 2 - - - Integer bitmask controlling data fusion and aiding methods - Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU delta velocity bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion. Cannot be used if bit position 7 is true. 5 : Set to true to enable multi-rotor drag specific force fusion 6 : set to true if the EV observations are in a non NED reference frame and need to be rotated before being used 7 : Set to true to enable GPS yaw fusion. Cannot be used if bit position 4 is true. - 0 - 511 - true - - use GPS - use optical flow - inhibit IMU bias estimation - vision position fusion - vision yaw fusion - multi-rotor drag fusion - rotate external vision - GPS yaw fusion - vision velocity fusion - - - - 1-sigma tilt angle uncertainty after gravity vector alignment - 0.0 - 0.5 - rad - 3 - true - - - Airspeed fusion threshold - A value of zero will deactivate airspeed fusion. Any other positive value will determine the minimum airspeed which will still be fused. Set to about 90% of the vehicles stall speed. Both airspeed fusion and sideslip fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_FUSE_BETA to activate sideslip fusion. - 0.0 - m/s - 1 - - - Upper limit on airspeed along individual axes used to correct baro for position error effects - 5.0 - 50.0 - m/s - 1 - - - Airspeed measurement delay relative to IMU measurements + + Airspeed measurement delay relative to IMU measurements 0 300 ms @@ -2061,13 +1661,17 @@ true - Auxillary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements + Auxiliary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements 0 300 ms 1 true + + Barometric sensor height aiding + If this parameter is enabled then the estimator will make use of the barometric height measurements to estimate its height in addition to other height sources (if activated). + Barometer measurement delay relative to IMU measurements 0 @@ -2092,7 +1696,7 @@ X-axis ballistic coefficient used for multi-rotor wind estimation - This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The EKF2_BCOEF_X paraemter should be set initially to the ratio of mass / projected frontal area and adjusted together with EKF2_MCOEF to minimise variance of the X-axis drag specific force innovation sequence. The drag produced by this effect scales with speed squared. Set this parameter to zero to turn off the bluff body drag model for this axis. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. + This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis. 0.0 200.0 kg/m^2 @@ -2100,7 +1704,7 @@ Y-axis ballistic coefficient used for multi-rotor wind estimation - This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The EKF2_BCOEF_Y paraemter should be set initially to the ratio of mass / projected side area and adjusted together with EKF2_MCOEF to minimise variance of the Y-axis drag specific force innovation sequence. The drag produced by this effect scales with speed squared. et this parameter to zero to turn off the bluff body drag model for this axis. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. + This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis. 0.0 200.0 kg/m^2 @@ -2132,6 +1736,10 @@ use declination as an observation + + Multirotor wind estimation selection + Activate wind speed estimation using specific-force measurements and a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles that have their thrust aligned with the Z axis and no thrust in the XY plane. + Specific drag force observation noise variance used by the multi-rotor specific drag force model Increasing this makes the multi-rotor wind estimates adjust more slowly. @@ -2147,7 +1755,7 @@ m/s 1 - + Measurement noise for vision angle observations used to lower bound or replace the uncertainty included in the message 0.05 rad @@ -2179,7 +1787,19 @@ m/s 2 - + + External vision (EV) sensor aiding + Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw + 0 + 15 + + Horizontal position + Vertical position + 3D velocity + Yaw + + + Vision Position Estimator delay relative to IMU measurements 0 300 @@ -2187,9 +1807,13 @@ 1 true - - Whether to set the external vision observation noise from the parameter or from vision message - If set to true the observation noise is set from the parameters directly, if set to false the measurement noise is taken from the vision message and the parameter are used as a lower bound. + + External vision (EV) noise mode + If set to 0 (default) the measurement noise is taken from the vision message and the EV noise parameters are used as a lower bound. If set to 1 the observation noise is set from the parameters directly, + + EV reported variance (parameter lower bound) + EV noise parameters + X position of VI sensor focal point in body frame (forward axis with origin relative to vehicle centre of gravity) @@ -2206,6 +1830,13 @@ m 3 + + External vision (EV) minimum quality (optional) + External vision will only be started and fused if the quality metric is above this threshold. The quality metric is a completely optional field provided by some VIO systems. + 0 + 100 + 1 + Boolean determining if synthetic sideslip measurements should fused A value of 1 indicates that fusion is active Both sideslip fusion and airspeed fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_ARSP_THR to activate airspeed fusion. @@ -2236,7 +1867,7 @@ Integer bitmask controlling GPS checks - Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Maximum allowed PDOP set by EKF2_REQ_PDOP 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT + Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Maximum allowed PDOP set by EKF2_REQ_PDOP 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT 0 511 @@ -2251,6 +1882,18 @@ Max vertical velocity discrepancy (EKF2_REQ_VDRIFT) + + GNSS sensor aiding + Set bits in the following positions to enable: 0 : Longitude and latitude fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading fusion + 0 + 15 + + Lon/lat + Altitude + 3D velocity + Dual antenna heading + + GPS measurement delay relative to IMU measurements 0 @@ -2302,14 +1945,29 @@ m/s 2 + + Accelerometer measurement noise for gravity based observations + 0.1 + 10.0 + m/s^2 + 2 + Default value of true airspeed used in EKF-GSF AHRS calculation - If no airspeed measurements are avalable, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes. + If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes. 0.0 100.0 m/s 1 + + Gyro bias learning limit + The ekf delta angle bias states will be limited to within a range equivalent to +- of this value. + 0.0 + 0.4 + rad/s + 3 + Process noise for IMU rate gyro bias prediction 0.0 @@ -2325,7 +1983,7 @@ 4 - Gate size for magnetic heading fusion + Gate size for heading fusion Sets the number of standard deviations used by the innovation consistency test. 1.0 SD @@ -2338,9 +1996,9 @@ rad 2 - - Determines the primary source of height data used by the EKF - The range sensor option should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. + + Determines the reference source of height data used by the EKF + When multiple height sources are enabled at the same time, the height estimate will always converge towards the reference height source selected by this parameter. The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. true Barometric pressure @@ -2349,6 +2007,16 @@ Vision + + IMU control + 0 + 7 + + Gyro Bias + Accel Bias + Gravity vector fusion + + X position of IMU in body frame (forward axis with origin relative to vehicle centre of gravity) m @@ -2366,7 +2034,7 @@ Horizontal acceleration threshold used by automatic selection of magnetometer fusion method - This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered horizontal acceleration is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion. + This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered horizontal acceleration is greater than this parameter value, then the EKF will use 3-axis magnetometer fusion. 0.0 5.0 m/s^2 @@ -2379,9 +2047,32 @@ gauss/s 6 - + Magnetic field strength test selection - When set, the EKF checks the strength of the magnetic field to decide whether the magnetometer data is valid. If GPS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. + Bitmask to set which check is used to decide whether the magnetometer data is valid. If GNSS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find the theoretical strength and inclination using the WMM + 0 + 7 + + Strength (EKF2_MAG_CHK_STR) + Inclination (EKF2_MAG_CHK_INC) + Wait for WMM + + + + Magnetic field inclination check tolerance + Maximum allowed deviation from the expected magnetic field inclination to pass the check. + 0.0 + 90.0 + deg + 1 + + + Magnetic field strength check tolerance + Maximum allowed deviation from the expected magnetic field strength to pass the check. + 0.0 + 1.0 + gauss + 2 Magnetic declination @@ -2419,55 +2110,37 @@ Type of magnetometer fusion - Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fuson of magnetomer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight with fallback to magnetic heading fusion if there is insufficient motion to make yaw or magnetic field states observable. If set to 'Magnetic heading' magnetic heading fusion is used at all times If set to '3-axis' 3-axis field fusion is used at all times. If set to 'VTOL custom' the behaviour is the same as 'Automatic', but if fusing airspeed, magnetometer fusion is only allowed to modify the magnetic field states. This can be used by VTOL platforms with large magnetic field disturbances to prevent incorrect bias states being learned during forward flight operation which can adversely affect estimation accuracy after transition to hovering flight. If set to 'MC custom' the behaviour is the same as 'Automatic, but if there are no earth frame position or velocity observations being used, the magnetometer will not be used. This enables vehicles to operate with no GPS in environments where the magnetic field cannot be used to provide a heading reference. Prior to flight, the yaw angle is assumed to be constant if movement tests controlled by the EKF2_MOVE_TEST parameter indicate that the vehicle is static. This allows the vehicle to be placed on the ground to learn the yaw gyro bias prior to flight. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality). Other external sources of yaw may be used if selected via the EKF2_AID_MASK parameter. + Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight with fallback to magnetic heading fusion if there is insufficient motion to make yaw or magnetic field states observable. If set to 'Magnetic heading' magnetic heading fusion is used at all times. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality). true Automatic Magnetic heading - 3-axis - VTOL custom - MC custom None - + Yaw rate threshold used by automatic selection of magnetometer fusion method - This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered yaw rate is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion. + This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered yaw rate is greater than this parameter value, then the EKF will use 3-axis magnetometer fusion. 0.0 1.0 rad/s 2 - propeller momentum drag coefficient used for multi-rotor wind estimation - This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_AID_MASK parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. For example, if flying at 10 m/s at sea level conditions produces a rotor induced drag deceleration of 1.5 m/s/s when the multi-copter levelled to zero roll/pitch, then EKF2_MCOEF would be set to 0.15 = (1.5/10.0). Set EKF2_MCOEF to a positive value to enable wind estimation using this drag effect. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. The EKF2_MCOEF parameter should be adjusted together with EKF2_BCOEF_X and EKF2_BCOEF_Y to minimise variance of the X and y axis drag specific force innovation sequences. + Propeller momentum drag coefficient used for multi-rotor wind estimation + This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. Set this parameter to zero to turn off the momentum drag model for both axis. 0 1.0 1/s 2 - - Minimum time of arrival delta between non-IMU observations before data is downsampled - Baro and Magnetometer data will be averaged before downsampling, other data will be point sampled resulting in loss of information. - 10 - 50 - ms - true - Expected range finder reading when on ground - If the vehicle is on ground, is not moving as determined by the motion test controlled by EKF2_MOVE_TEST and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is avilable at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground. + If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground. 0.01 m 2 - - Vehicle movement test threshold - Scales the threshold tests applied to IMU data used to determine if the vehicle is static or moving. See parameter descriptions for EKF2_GPS_CHECK and EKF2_MAG_TYPE for further information on the functionality affected by this parameter. - 0.1 - 10.0 - 1 - Multi-EKF IMUs Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. Requires SENS_IMU_MODE 0. @@ -2495,6 +2168,10 @@ 10000000 us + + Optical flow aiding + Enable optical flow fusion. + Optical flow measurement delay relative to IMU measurements Assumes measurement is timestamped at trailing edge of integration period @@ -2540,7 +2217,12 @@ 3 - Optical Flow data will only be used if the sensor reports a quality metric >= EKF2_OF_QMIN + Optical Flow data will only be used in air if the sensor reports a quality metric >= EKF2_OF_QMIN + 0 + 255 + + + Optical Flow data will only be used on the ground if the sensor reports a quality metric >= EKF2_OF_QMIN_GND 0 255 @@ -2579,6 +2261,13 @@ 0.5 2 + + EKF prediction period + EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. Actual filter update will be an integer multiple of IMU update. + 1000 + 20000 + us + Required EPH to use GPS 2 @@ -2633,17 +2322,9 @@ m/s 2 - - Range sensor aid - If this parameter is enabled then the estimator will make use of the range finder measurements to estimate it's height even if range sensor is not the primary height source. It will only do so if conditions for range measurement fusion are met. This enables the range finder to be used during low speed and low altitude operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX. If vehicle motion causes repeated switching between the primary height sensor and range finder, an offset in the local position origin can accumulate. Also range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. - - Range aid disabled - Range aid enabled - - - Maximum absolute altitude (height above ground level) allowed for range aid mode - If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled). + Maximum absolute altitude (height above ground level) allowed for conditional range aid mode + If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). 1.0 10.0 m @@ -2656,12 +2337,21 @@ SD - Maximum horizontal velocity allowed for range aid mode - If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled). + Maximum horizontal velocity allowed for conditional range aid mode + If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). 0.1 2 m/s + + Range sensor height aiding + WARNING: Range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. To en-/disable range finder for terrain height estimation, use EKF2_TERR_MASK instead. If this parameter is enabled then the estimator will make use of the range finder measurements to estimate its height in addition to other height sources (if activated). Range sensor aiding can be enabled (i.e.: always use) or set in "conditional" mode. Conditional mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX. + + Disable range fusion + Enabled (conditional mode) + Enabled + + Range finder measurement delay relative to IMU measurements 0 @@ -2677,6 +2367,13 @@ SD 1 + + Gate size used for range finder kinematic consistency check + To be used, the time derivative of the distance sensor measurements projected on the vertical axis needs to be statistically consistent with the estimated vertical velocity of the drone. Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate. + 0.1 + 5.0 + SD + Measurement noise for range finder fusion 0.01 @@ -2712,7 +2409,7 @@ s - Range finder range dependant noise scaler + Range finder range dependent noise scaler Specifies the increase in range finder noise with range. 0.0 0.2 @@ -2744,7 +2441,7 @@ Enable synthetic magnetometer Z component measurement - Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ingored instead of fusing the synthetic value. + Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value. Gate size for TAS fusion @@ -2788,11 +2485,12 @@ m/s 1 - - Process noise for wind velocity prediction + + Process noise spectral density for wind velocity prediction + When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. 0.0 1.0 - m/s^2 + m/s^2/sqrt(Hz) 3 @@ -2826,218 +2524,31 @@ - - Acro body x max rate - This is the rate the controller is trying to achieve if the user applies full roll stick input in acro mode. - 45 - 720 - deg - - - Acro body y max rate - This is the body y rate the controller is trying to achieve if the user applies full pitch stick input in acro mode. - 45 - 720 - deg - - - Acro body z max rate - This is the body z rate the controller is trying to achieve if the user applies full yaw stick input in acro mode. - 10 - 180 - deg - - - Airspeed mode - For small wings or VTOL without airspeed sensor this parameter can be used to enable flying without an airspeed reading - - Normal (use airspeed if available) - Airspeed disabled - - - - Enable airspeed scaling - This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro) - - - Whether to scale throttle by battery power level - This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The fixed wing should constantly behave as if it was fully charged with reduced max thrust at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery. - - - Pitch trim increment for flaps configuration - This increment is added to the pitch trim whenever flaps are fully deployed. - -0.25 - 0.25 - 2 - 0.01 - - - Pitch trim increment at maximum airspeed - This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX. - -0.25 - 0.25 - 2 - 0.01 - - - Pitch trim increment at minimum airspeed - This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN. - -0.25 - 0.25 - 2 - 0.01 - - - Roll trim increment for flaps configuration - This increment is added to TRIM_ROLL whenever flaps are fully deployed. - -0.25 - 0.25 - 2 - 0.01 - - - Roll trim increment at maximum airspeed - This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX. - -0.25 - 0.25 - 2 - 0.01 - - - Roll trim increment at minimum airspeed - This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN. - -0.25 - 0.25 - 2 - 0.01 - - - Yaw trim increment at maximum airspeed - This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX. - -0.25 - 0.25 - 2 - 0.01 - - - Yaw trim increment at minimum airspeed - This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN. - -0.25 - 0.25 - 2 - 0.01 - - - Scale factor for flaperons - 0.0 - 1.0 - norm - 2 - 0.01 - - - Flaps setting during landing - Sets a fraction of full flaps (FW_FLAPS_SCL) during landing - 0.0 - 1.0 - norm - 2 - 0.01 - - - Scale factor for flaps - 0.0 - 1.0 - norm - 2 - 0.01 - - - Flaps setting during take-off - Sets a fraction of full flaps (FW_FLAPS_SCL) during take-off - 0.0 - 1.0 - norm - 2 - 0.01 - - - Max manual pitch - Max pitch for manual control in attitude stabilized mode + + Maximum manual pitch angle + Maximum manual pitch angle setpoint (positive & negative) in manual attitude-only stabilized mode 0.0 90.0 deg 1 0.5 - - Manual pitch scale - Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. - 0.0 - norm - 2 - 0.01 - - Max manual roll - Max roll for manual control in attitude stabilized mode + Maximum manual roll angle + Maximum manual roll angle setpoint (positive & negative) in manual attitude-only stabilized mode 0.0 90.0 deg 1 0.5 - - Manual roll scale - Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. - 0.0 - 1.0 - norm - 2 - 0.01 - - - Manual yaw scale - Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. - 0.0 - norm - 2 - 0.01 - - - Pitch rate feed forward - Direct feed forward from rate setpoint to control surface output - 0.0 - 10.0 - %/rad/s - 2 - 0.05 - - - Pitch rate integrator gain - This gain defines how much control response will result out of a steady state error. It trims any constant error. - 0.005 - 0.5 - %/rad - 3 - 0.005 - - - Pitch rate integrator limit - The portion of the integrator part in the control surface deflection is limited to this value - 0.0 - 1.0 - 2 - 0.05 - - - Pitch rate proportional gain - This defines how much the elevator input will be commanded depending on the current body angular rate error. - 0.005 - 1.0 - %/rad/s - 3 - 0.005 + + Maximum manually added yaw rate + This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode. The controller already generates a yaw rate setpoint to coordinate a turn, and this value is added to it. This is an absolute value, which is applied symmetrically to the negative and positive side. + 0 + deg/s + 1 + 0.5 Pitch setpoint offset (pitch at level flight) @@ -3049,19 +2560,17 @@ 0.5 - Maximum negative / down pitch rate - This limits the maximum pitch down up angular rate the controller will output (in degrees per second). + Maximum negative / down pitch rate setpoint 0.0 - 90.0 + 180 deg/s 1 0.5 - Maximum positive / up pitch rate - This limits the maximum pitch up angular rate the controller will output (in degrees per second). + Maximum positive / up pitch rate setpoint 0.0 - 90.0 + 180 deg/s 1 0.5 @@ -3075,53 +2584,10 @@ 2 0.05 - - Roll control to yaw control feedforward gain - This gain can be used to counteract the "adverse yaw" effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator (rudder, airbrakes, ...) to counteract this effect. - 0.0 - 1 - 0.01 - - - Roll rate feed forward - Direct feed forward from rate setpoint to control surface output. Use this to obtain a tigher response of the controller without introducing noise amplification. - 0.0 - 10.0 - %/rad/s - 2 - 0.05 - - - Roll rate integrator Gain - This gain defines how much control response will result out of a steady state error. It trims any constant error. - 0.005 - 0.2 - %/rad - 3 - 0.005 - - - Roll integrator anti-windup - The portion of the integrator part in the control surface deflection is limited to this value. - 0.0 - 1.0 - 2 - 0.05 - - - Roll rate proportional Gain - This defines how much the aileron input will be commanded depending on the current body angular rate error. - 0.005 - 1.0 - %/rad/s - 3 - 0.005 - - Maximum roll rate - This limits the maximum roll rate the controller will output (in degrees per second). + Maximum roll rate setpoint 0.0 - 90.0 + 180 deg/s 1 0.5 @@ -3129,17 +2595,33 @@ Attitude Roll Time Constant This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed. - 0.4 + 0.2 1.0 s 2 0.05 + + Spoiler descend setting + 0.0 + 1.0 + norm + 2 + 0.01 + + + Spoiler landing setting + 0.0 + 1.0 + norm + 2 + 0.01 + Wheel steering rate feed forward Direct feed forward from rate setpoint to control surface output 0.0 - 10.0 + 10 %/rad/s 2 0.05 @@ -3147,13 +2629,13 @@ Wheel steering rate integrator gain This gain defines how much control response will result out of a steady state error. It trims any constant error. - 0.005 - 0.5 + 0.0 + 10 %/rad 3 0.005 - + Wheel steering rate integrator limit The portion of the integrator part in the control surface deflection is limited to this value 0.0 @@ -3164,14 +2646,15 @@ Wheel steering rate proportional gain This defines how much the wheel steering input will be commanded depending on the current body angular rate error. - 0.005 - 1.0 + 0.0 + 10 %/rad/s 3 0.005 Enable wheel steering controller + Only enabled during automatic runway takeoff and landing. In all manual modes the wheel is directly controlled with yaw stick. Maximum wheel steering rate @@ -3182,96 +2665,37 @@ 1 0.5 - - Yaw rate feed forward - Direct feed forward from rate setpoint to control surface output + + Maximum yaw rate setpoint 0.0 - 10.0 - %/rad/s - 2 - 0.05 - - - Yaw rate integrator gain - This gain defines how much control response will result out of a steady state error. It trims any constant error. - 0.0 - 50.0 - %/rad - 1 - 0.5 - - - Yaw rate integrator limit - The portion of the integrator part in the control surface deflection is limited to this value - 0.0 - 1.0 - 2 - 0.05 - - - Yaw rate proportional gain - This defines how much the rudder input will be commanded depending on the current body angular rate error. - 0.005 - 1.0 - %/rad/s - 3 - 0.005 - - - Maximum yaw rate - This limits the maximum yaw rate the controller will output (in degrees per second). - 0.0 - 90.0 + 180 deg/s 1 0.5 - - - Climbout Altitude difference - If the altitude error exceeds this parameter, the system will climb out with maximum throttle and minimum airspeed until it is closer than this distance to the desired altitude. Mostly used for takeoff waypoints / modes. Set to 0 to disable climbout mode (not recommended). - 0.0 - 150.0 - m - 1 - 0.5 - - - L1 damping - Damping factor for L1 control. - 0.6 - 0.9 - 2 - 0.05 - - - L1 period - This is the L1 distance and defines the tracking point ahead of the aircraft its following. A value of 18-25 meters works for most aircraft. Shorten slowly during tuning until response is sharp without oscillation. - 12.0 - 50.0 - m - 1 - 0.5 - - - L1 controller roll slew rate limit - The maxium change in roll angle setpoint per second. + + + Bit mask to set the automatic landing abort conditions + Terrain estimation: bit 0: Abort if terrain is not found bit 1: Abort if terrain times out (after a first successful measurement) The last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the selected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored. TODO: Extend automatic abort conditions e.g. glide slope tracking error (horizontal and vertical) 0 - deg/s - 1 + 3 + + Abort if terrain is not found (only applies to mission landings) + Abort if terrain times out (after a first successful measurement) + - - Min. airspeed scaling factor for landing - Multiplying this factor with the minimum airspeed of the plane gives the target airspeed the landing approach. FW_AIRSPD_MIN * FW_LND_AIRSPD_SC - 1.0 - 1.5 - norm - 2 - 0.01 + + Landing airspeed + The calibrated airspeed setpoint during landing. If set <= 0.0, landing airspeed = FW_AIRSPD_MIN by default. + -1.0 + m/s + 1 + 0.1 - Landing slope angle + Maximum landing slope angle + Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled. Set this value within the vehicle's performance limits. 1.0 15.0 deg @@ -3282,17 +2706,17 @@ Early landing configuration deployment When disabled, the landing configuration (flaps, landing airspeed, etc.) is only activated on the final approach to landing. When enabled, it is already activated when entering the final loiter-down (loiter-to-alt) waypoint before the landing approach. This shifts the (often large) altitude and airspeed errors caused by the configuration change away from the ground such that these are not so critical. It also gives the controller enough time to adapt to the new configuration such that the landing approach starts with a cleaner initial state. - + Landing flare altitude (relative to landing altitude) + NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * |z-velocity|) is taken as the flare altitude 0.0 - 25.0 m 1 0.5 Flare, maximum pitch - Maximum pitch during flare, a positive sign means nose up Applied once FW_LND_FLALT is reached + Maximum pitch during flare, a positive sign means nose up Applied once flaring is triggered 0 45.0 deg @@ -3301,146 +2725,227 @@ Flare, minimum pitch - Minimum pitch during flare, a positive sign means nose up Applied once FW_LND_FLALT is reached - 0 + Minimum pitch during flare, a positive sign means nose up Applied once flaring is triggered + -5 15.0 deg 1 0.5 - - Landing heading hold horizontal distance - Set to 0 to disable heading hold. + + Landing flare sink rate + TECS will attempt to control the aircraft to this sink rate via pitch angle (throttle killed during flare) + 0.0 + 2 + m/s + 2 + 0.1 + + + Landing flare time + Multiplied by the descent rate to calculate a dynamic altitude at which to trigger the flare. NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * descent rate) is taken as the flare altitude + 0.1 + 5.0 + s + 1 + 0.1 + + + Landing touchdown nudging option + Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant Approach path nudging: shifts the touchdown point laterally along with the entire approach path This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the desired landing vector. Nuding is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle). 0 - 30.0 + 2 + + Disable nudging + Nudge approach angle + Nudge approach path + + + + Maximum lateral position offset for the touchdown point + 0.0 + 10.0 m 1 - 0.5 + 1 - - FW_LND_HVIRT - 1.0 - 15.0 - m + + Landing touchdown time (since flare start) + This is the time after the start of flaring that we expect the vehicle to touch the runway. At this time, a 0.5s clamp down ramp will engage, constraining the pitch setpoint to RWTO_PSP. If enabled, ensure that RWTO_PSP is configured appropriately for full gear contact on ground roll. Set to -1.0 to disable touchdown clamping. E.g. it may not be desirable to clamp on belly landings. The touchdown time will be constrained to be greater than or equal to the flare time (FW_LND_FL_TIME). + -1.0 + 5.0 + s 1 - 0.5 + 0.1 Altitude time constant factor for landing - Set this parameter to less than 1.0 to make TECS react faster to altitude errors during landing than during normal flight (i.e. giving efficiency and low motor wear at high altitudes but control accuracy during landing). During landing, the TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value. + Set this parameter to less than 1.0 to make TECS react faster to altitude errors during landing than during normal flight. During landing, the TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value. 0.2 1.0 0.1 - - Landing throttle limit altitude (relative landing altitude) - Default of -1.0 lets the system default to applying throttle limiting at 2/3 of the flare altitude. - -1.0 - 30.0 - m - 1 - 0.5 - - - Use terrain estimate during landing - This is turned off by default and a waypoint or return altitude is normally used (or sea level for an arbitrary land position). - - - RC stick mapping fixed-wing - Set RC/joystick configuration for fixed-wing position and altitude controlled flight. + + Use terrain estimation during landing. This is critical for detecting when to flare, and should be enabled if possible + NOTE: terrain estimate is currently solely derived from a distance sensor. If enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing will be aborted, depending on the criteria set in FW_LND_ABORT. If disabled, FW_LND_ABORT terrain based criteria are ignored. 0 - 1 + 2 - Normal stick configuration (airspeed on throttle stick, altitude on pitch stick) - Alternative stick configuration (altitude on throttle stick, airspeed on pitch stick) + Disable the terrain estimate + Use the terrain estimate to trigger the flare (only) + Calculate landing glide slope relative to the terrain estimate - - Positive pitch limit - The maximum positive pitch the controller will output. + + + + Height (AGL) of the wings when the aircraft is on the ground + This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer to give a slight margin here (> 0m) 0.0 - 60.0 - deg + m 1 - 0.5 + 1 - - Negative pitch limit - The minimum negative pitch the controller will output. - -60.0 - 0.0 - deg + + The aircraft's wing span (length from tip to tip) + This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span) + 0.1 + m 1 - 0.5 + 0.1 - - Controller roll limit - The maximum roll the controller will output. - 35.0 - 65.0 - deg + + + + Trigger time + Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds. + 0.0 + 5.0 + s + 2 + 0.05 + + + Trigger acceleration threshold + Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds. + 0 + m/s^2 1 0.5 - - Scale throttle by pressure change - Automatically adjust throttle to account for decreased air density at higher altitudes. Start with a scale factor of 1.0 and adjust for different propulsion systems. When flying without airspeed sensor this will help to keep a constant performance over large altitude ranges. The default value of 0 will disable scaling. + + FW Launch detection + Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles. Only available for fixed-wing vehicles. Not compatible with runway takeoff. + + + Motor delay + Start the motor(s) this amount of seconds after launch is detected. 0.0 10.0 + s 1 - 0.1 + 0.5 - - Cruise throttle - This is the throttle setting required to achieve the desired cruise speed. Most airframes have a value of 0.5-0.7. - 0.0 - 1.0 - norm + + + + NPFG damping ratio + Damping ratio of the NPFG control law. + 0.10 + 1.00 2 0.01 - - Idle throttle - This is the minimum throttle while on the ground For aircraft with internal combustion engine this parameter should be set above desired idle rpm. - 0.0 - 0.4 - norm - 2 - 0.01 + + Enable minimum forward ground speed maintaining excess wind handling logic - - Throttle limit during landing below throttle limit altitude - During the flare of the autonomous landing process, this value will be set as throttle limit when the aircraft altitude is below FW_LND_TLALT. + + Maximum, minimum forward ground speed for track keeping in excess wind + The maximum value of the minimum forward ground speed that may be commanded by the track keeping excess wind handling logic. Commanded in full at the normalized track error fraction of the track error boundary and reduced to zero on track. 0.0 - 1.0 - norm - 2 - 0.01 + 10.0 + m/s + 1 + 0.5 - - Throttle limit max - This is the maximum throttle % that can be used by the controller. For overpowered aircraft, this should be reduced to a value that provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX. - 0.0 - 1.0 - norm + + Enable automatic lower bound on the NPFG period + Avoids limit cycling from a too aggressively tuned period/damping combination. If set to false, also disables the upper bound NPFG_PERIOD_UB. + + + NPFG period + Period of the NPFG control law. + 1.0 + 100.0 + s + 1 + 0.1 + + + Period safety factor + Multiplied by period for conservative minimum period bounding (when period lower bounding is enabled). 1.0 bounds at marginal stability. + 1.0 + 10.0 + 1 + 0.1 + + + Roll time constant + Time constant of roll controller command / response, modeled as first order delay. Used to determine lower period bound. Setting zero disables automatic period bounding. + 0.00 + 2.00 + s 2 - 0.01 + 0.05 - - Throttle limit min - This is the minimum throttle % that can be used by the controller. For electric aircraft this will normally be set to zero, but can be set to a small non-zero value if a folding prop is fitted to prevent the prop from folding and unfolding repeatedly in-flight or to provide some aerodynamic drag from a turning prop to improve the descent rate. For aircraft with internal combustion engine this parameter should be set for desired idle rpm. - 0.0 + + NPFG switch distance multiplier + Multiplied by the track error boundary to determine when the aircraft switches to the next waypoint and/or path segment. Should be less than 1. + 0.1 1.0 - norm 2 0.01 - - Throttle max slew rate - Maximum slew rate for the commanded throttle - 0.0 - 1.0 + + Enable track keeping excess wind handling logic + + + Enable automatic upper bound on the NPFG period + Adapts period to maintain track keeping in variable winds and path curvature. + + + Enable wind excess regulation + Disabling this parameter further disables all other airspeed incrementation options. + + + + + Path navigation roll slew rate limit + The maximum change in roll angle setpoint per second. + 0 + deg/s + 0 + 1 + + + RC stick configuration fixed-wing + Set RC/joystick configuration for fixed-wing manual position and altitude controlled flight. + 0 + 3 + + Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick) + Enable airspeed setpoint via sticks in altitude and position flight mode + + + + Maximum roll angle + The maximum roll angle setpoint for setpoint for a height-rate or altitude controlled mode. + 35.0 + 65.0 + deg + 1 + 0.5 Minimum pitch during takeoff @@ -3451,3685 +2956,2874 @@ 0.5 - - - Launch detection + + + Acro body x max rate + This is the rate the controller is trying to achieve if the user applies full roll stick input in acro mode. + 10 + 720 + deg - - Catapult accelerometer threshold - LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection. - 0 - m/s^2 - 1 - 0.5 + + Enable yaw rate controller in Acro + If this parameter is set to 1, the yaw rate controller is enabled in Fixed-wing Acro mode. Otherwise the pilot commands directly the yaw actuator. It is disabled by default because an active yaw rate controller will fight against the natural turn coordination of the plane. - - Motor delay - Delay between starting attitude control and powering up the throttle (giving throttle control to the controller) Before this timespan is up the throttle will be set to FW_THR_IDLE, set to 0 to deactivate - 0.0 - 10.0 - s - 1 - 0.5 + + Acro body pitch max rate setpoint + 10 + 720 + deg - - Maximum pitch before the throttle is powered up (during motor delay phase) - This is an extra limit for the maximum pitch which is imposed in the phase before the throttle turns on. This allows to limit the maximum pitch angle during a bungee launch (make the launch less steep). - 0.0 - 45.0 + + Acro body yaw max rate setpoint + 10 + 720 deg - 1 - 0.5 - - Catapult time threshold - LAUN_CAT_A for LAUN_CAT_T serves as threshold to trigger launch detection. - 0.0 - 5.0 - s - 2 - 0.05 + + Airspeed mode + On vehicles without airspeed sensor this parameter can be used to enable flying without an airspeed reading + + Use airspeed in controller + Do not use airspeed in controller + - - - - Maximum Airspeed (CAS) - If the CAS (calibrated airspeed) is above this value, the TECS controller will try to decrease airspeed more aggressively. - 0.5 - 40 - m/s - 1 - 0.5 + + Enable airspeed scaling + This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro) - - Minimum Airspeed (CAS) - The minimal airspeed (calibrated airspeed) the user is able to command. Further, if the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. - 0.5 - 40 - m/s - 1 - 0.5 + + Enable throttle scale by battery level + This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. - - Stall Airspeed (CAS) - The stall airspeed (calibrated airspeed) of the vehicle. It is used for airspeed sensor failure detection and for the control surface scaling airspeed limits. - 0.5 - 40 - m/s - 1 - 0.5 + + Pitch trim increment at maximum airspeed + This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX. + -0.5 + 0.5 + 2 + 0.01 - - Cruise Airspeed (CAS) - The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active, this is the default airspeed setpoint that the controller will try to achieve if no other airspeed setpoint sources are present (e.g. through non-centered RC sticks). - 0.5 - 40 - m/s - 1 - 0.5 + + Pitch trim increment at minimum airspeed + This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN. + -0.5 + 0.5 + 2 + 0.01 - - Minimum groundspeed - The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint. - 0.0 - 40 - m/s - 1 - 0.5 + + Roll trim increment at maximum airspeed + This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX. + -0.5 + 0.5 + 2 + 0.01 - - Altitude error time constant - 2.0 + + Roll trim increment at minimum airspeed + This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN. + -0.5 + 0.5 2 - 0.5 + 0.01 - - Maximum climb rate - This is the best climb rate that the aircraft can achieve with the throttle set to THR_MAX and the airspeed set to the default value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced. The setting of this parameter can be checked by commanding a positive altitude change of 100m in loiter, RTL or guided mode. If the throttle required to climb is close to THR_MAX and the aircraft is maintaining airspeed, then this parameter is set correctly. If the airspeed starts to reduce, then the parameter is set to high, and if the throttle demand required to climb and maintain speed is noticeably less than FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or FW_THR_MAX reduced. - 1.0 - 15.0 - m/s - 1 - 0.5 + + Yaw trim increment at maximum airspeed + This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX. + -0.5 + 0.5 + 2 + 0.01 - - Default target climbrate - The default rate at which the vehicle will climb in autonomous modes to achieve altitude setpoints. In manual modes this defines the maximum rate at which the altitude setpoint can be increased. - 0.5 - 15 - m/s + + Yaw trim increment at minimum airspeed + This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN. + -0.5 + 0.5 2 0.01 - - Height rate feed forward + + Flaps setting during landing + Sets a fraction of full flaps during landing. Also applies to flaperons if enabled in the mixer/allocation. 0.0 1.0 + norm 2 - 0.05 + 0.01 - - Integrator gain pitch - This is the integrator gain on the pitch part of the control loop. Increasing this gain increases the speed at which speed and height offsets are trimmed out, but reduces damping and increases overshoot. Set this value to zero to completely disable all integrator action. + + Flaps setting during take-off + Sets a fraction of full flaps during take-off. Also applies to flaperons if enabled in the mixer/allocation. 0.0 - 2.0 + 1.0 + norm 2 - 0.05 + 0.01 - - Integrator gain throttle - This is the integrator gain on the throttle part of the control loop. Increasing this gain increases the speed at which speed and height offsets are trimmed out, but reduces damping and increases overshoot. Set this value to zero to completely disable all integrator action. + + Manual pitch scale + Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. 0.0 - 2.0 + norm 2 - 0.05 + 0.01 - - Pitch damping factor - This is the damping gain for the pitch demand loop. Increase to add damping to correct for oscillations in height. The default value of 0.0 will work well provided the pitch to servo controller has been tuned properly. + + Manual roll scale + Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. 0.0 - 2.0 + 1.0 + norm 2 - 0.1 + 0.01 - - Roll -> Throttle feedforward - Increasing this gain turn increases the amount of throttle that will be used to compensate for the additional drag created by turning. Ideally this should be set to approximately 10 x the extra sink rate in m/s created by a 45 degree bank turn. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns. Efficient high aspect-ratio aircraft (eg powered sailplanes) can use a lower value, whereas inefficient low aspect-ratio models (eg delta wings) can use a higher value. + + Manual yaw scale + Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. 0.0 - 20.0 - 1 - 0.5 - - - Specific total energy balance rate feedforward gain - 0.5 - 3 + norm 2 0.01 - - Maximum descent rate - This sets the maximum descent rate that the controller will use. If this value is too large, the aircraft can over-speed on descent. This should be set to a value that can be achieved without exceeding the lower pitch angle limit and without over-speeding the aircraft. - 1.0 - 15.0 - m/s - 1 - 0.5 + + Pitch rate derivative gain + Pitch rate differential gain. + 0.0 + 10 + %/rad/s + 3 + 0.005 - - Minimum descent rate - This is the sink rate of the aircraft with the throttle set to THR_MIN and flown at the same airspeed as used to measure FW_T_CLMB_MAX. - 1.0 - 5.0 - m/s - 1 - 0.5 + + Pitch rate feed forward + Direct feed forward from rate setpoint to control surface output + 0.0 + 10.0 + %/rad/s + 2 + 0.05 - - Default target sinkrate - The default rate at which the vehicle will sink in autonomous modes to achieve altitude setpoints. In manual modes this defines the maximum rate at which the altitude setpoint can be decreased. - 0.5 - 15 - m/s + + Pitch rate integrator gain + This gain defines how much control response will result out of a steady state error. It trims any constant error. + 0.0 + 10 + %/rad + 3 + 0.005 + + + Pitch rate integrator limit + The portion of the integrator part in the control surface deflection is limited to this value + 0.0 + 1.0 2 - 0.01 + 0.05 - - Speed <--> Altitude priority - This parameter adjusts the amount of weighting that the pitch control applies to speed vs height errors. Setting it to 0.0 will cause the pitch control to control height and ignore speed errors. This will normally improve height accuracy but give larger airspeed errors. Setting it to 2.0 will cause the pitch control loop to control speed and ignore height errors. This will normally reduce airspeed errors, but give larger height errors. The default value of 1.0 allows the pitch control to simultaneously control height and speed. Note to Glider Pilots - set this parameter to 2.0 (The glider will adjust its pitch angle to maintain airspeed, ignoring changes in height). + + Pitch rate proportional gain 0.0 - 2.0 - 1 - 1.0 + 10 + %/rad/s + 3 + 0.005 - - Complementary filter "omega" parameter for speed - This is the cross-over frequency (in radians/second) of the complementary filter used to fuse longitudinal acceleration and airspeed to obtain an improved airspeed estimate. Increasing this frequency weights the solution more towards use of the airspeed sensor, whilst reducing it weights the solution more towards use of the accelerometer data. - 1.0 - 10.0 - rad/s + + Roll control to yaw control feedforward gain + This gain can be used to counteract the "adverse yaw" effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator to counteract this effect. + 0.0 1 - 0.5 + 0.01 - - Specific total energy rate first order filter time constant - This filter is applied to the specific total energy rate used for throttle damping. + + Roll rate derivative Gain + Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. 0.0 - 2 + 10 + %/rad/s + 3 + 0.005 + + + Roll rate feed forward + Direct feed forward from rate setpoint to control surface output. Use this to obtain a tigher response of the controller without introducing noise amplification. + 0.0 + 10.0 + %/rad/s 2 - 0.01 + 0.05 - - True airspeed rate first order filter time constant - This filter is applied to the true airspeed rate. + + Roll rate integrator Gain + This gain defines how much control response will result out of a steady state error. It trims any constant error. 0.0 - 2 + 10 + %/rad 2 0.01 - - True airspeed error time constant - 2.0 + + Roll integrator anti-windup + The portion of the integrator part in the control surface deflection is limited to this value. + 0.0 + 1.0 2 - 0.5 + 0.05 - - Throttle damping factor - This is the damping gain for the throttle demand loop. Increase to add damping to correct for oscillations in speed and height. + + Roll rate proportional Gain 0.0 - 2.0 - 2 - 0.1 + 10 + %/rad/s + 3 + 0.005 - - Maximum vertical acceleration - This is the maximum vertical acceleration (in m/s/s) either up or down that the controller will use to correct speed or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) allows for reasonably aggressive pitch changes if required to recover from under-speed conditions. - 1.0 - 10.0 - m/s^2 - 1 - 0.5 - - - - - Enable checks on ESCs that report their arming state - If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle. - - - Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS) - Enabled on either AUX5 or MAIN5 depending on board. External ATS is required by ASTM F3322-18. - true - - - The PWM threshold from external automatic trigger system for engaging failsafe - External ATS is required by ASTM F3322-18. - us - 2 - - - FailureDetector Max Pitch - Maximum pitch angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check - 60 - 180 - deg - - - Pitch failure trigger time - Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure. - 0.02 - 5 - s - 2 + + Spoiler input in manual flight + Chose source for manual setting of spoilers in manual flight modes. + + Disabled + Flaps channel + Aux1 + - - FailureDetector Max Roll - Maximum roll angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check - 60 - 180 - deg + + Yaw rate derivative gain + Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + 0.0 + 10 + %/rad/s + 3 + 0.005 - - Roll failure trigger time - Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure. - 0.02 - 5 - s + + Yaw rate feed forward + Direct feed forward from rate setpoint to control surface output + 0.0 + 10.0 + %/rad/s 2 + 0.05 - - - - Distance to follow target from - The distance in meters to follow the target at - 1.0 - m - - - Side to follow target from - The side to follow the target from (front right = 0, behind = 1, front = 2, front left = 3) - 0 - 3 + + Yaw rate integrator gain + This gain defines how much control response will result out of a steady state error. It trims any constant error. + 0.0 + 10 + %/rad + 1 + 0.5 - - Dynamic filtering algorithm responsiveness to target movement - lower numbers increase the responsiveness to changing long lat but also ignore less noise + + Yaw rate integrator limit + The portion of the integrator part in the control surface deflection is limited to this value 0.0 1.0 2 + 0.05 - - Minimum follow target altitude - The minimum height in meters relative to home for following a target - 8.0 - m + + Yaw rate proportional gain + 0.0 + 10 + %/rad/s + 3 + 0.005 - - - Serial Configuration for Main GPS - Configure on which serial port to run Main GPS. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - - - GNSS Systems for Primary GPS (integer bitmask) - This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS - 0 - 31 - true - - GPS (with QZSS) - SBAS - Galileo - BeiDou - GLONASS - - - - Protocol for Main GPS - Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower. - 0 - 5 - true - - Auto detect - u-blox - MTK - Ashtech / Trimble - Emlid Reach - Femtomes - NMEA (generic) - - - - Serial Configuration for Secondary GPS - Configure on which serial port to run Secondary GPS. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - - - GNSS Systems for Secondary GPS (integer bitmask) - This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS - 0 - 31 - true - - GPS (with QZSS) - SBAS - Galileo - BeiDou - GLONASS - - - - Protocol for Secondary GPS - Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower. - 0 - 5 - true - - Auto detect - u-blox - MTK - Ashtech / Trimble - Emlid Reach - Femtomes - NMEA (generic) - - - - Log GPS communication data - If this is set to 1, all GPS communication data will be published via uORB, and written to the log file as gps_dump message. If this is set to 2, the main GPS is configured to output RTCM data, which is then logged as gps_dump and can be used for PPK. - 0 - 2 - - Disable - Full communication - RTCM output (PPK) - + + + Maximum Airspeed (CAS) + The maximal airspeed (calibrated airspeed) the user is able to command. + 0.5 + m/s + 1 + 0.5 - - u-blox GPS dynamic platform model - u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment. - 0 - 9 - true - - stationary - automotive - airborne with <1g acceleration - airborne with <2g acceleration - airborne with <4g acceleration - + + Minimum Airspeed (CAS) + The minimal airspeed (calibrated airspeed) the user is able to command. Further, if the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. Has to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL), with some margin between the stall speed and minimum airspeed. This value corresponds to the desired minimum speed with the default load factor (level flight, default weight), and is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE). + 0.5 + m/s + 1 + 0.5 - - u-blox GPS Mode - Select the u-blox configuration setup. Most setups will use the default, including RTK and dual GPS without heading. The Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output heading information, whereas the secondary will act as moving base, sending RTCM on UART2 to the rover GPS. RTK is still possible with this setup. - 0 - 1 - true - - Default - Heading - + + Stall Airspeed (CAS) + The stall airspeed (calibrated airspeed) of the vehicle. It is used for airspeed sensor failure detection and for the control surface scaling airspeed limits. + 0.5 + m/s + 1 + 0.5 - - Heading/Yaw offset for dual antenna GPS - Heading offset angle for dual antenna GPS setups that support heading estimation. (currently only for the Trimble MB-Two). Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the first antenna is in front. The offset angle increases clockwise. Set this to 90 if the first antenna is placed on the right side and the second on the left side of the vehicle. - 0 - 360 - deg - 0 - true + + Trim (Cruise) Airspeed + The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active, this is the default airspeed setpoint that the controller will try to achieve. + 0.5 + m/s + 1 + 0.5 - - - - Loiter time - The time in seconds the system should do open loop loiter and wait for GPS recovery before it goes into flight termination. Set to 0 to disable. + + Minimum groundspeed + The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint. 0.0 - 3600.0 - s - 0 - 1 + 40 + m/s + 1 + 0.5 - - Fixed pitch angle - Pitch in degrees during the open loop loiter - -30.0 - 30.0 + + Maximum pitch angle + The maximum pitch angle setpoint setpoint for a height-rate or altitude controlled mode. + 0.0 + 60.0 deg 1 0.5 - - Fixed bank angle - Roll in degrees during the loiter - 0.0 - 30.0 + + Minimum pitch angle + The minimum pitch angle setpoint for a height-rate or altitude controlled mode. + -60.0 + 0.0 deg 1 0.5 - - Thrust - Thrust value which is set during the open loop loiter - 0.0 - 1.0 - norm + + Throttle at max airspeed + Required throttle for level flight at maximum airspeed FW_AIRSPD_MAX (sea level, standard atmosphere) Set to 0 to disable mapping of airspeed to trim throttle. + 0 + 1 2 - 0.05 + 0.01 - - - - Geofence violation action - Note: Setting this value to 4 enables flight termination, which will kill the vehicle on violation of the fence. Due to the inherent danger of this, this function is disabled using a software circuit breaker, which needs to be reset to 0 to really shut down the system. - 0 - 5 - - None - Warning - Hold mode - Return mode - Terminate - Land mode - - - - Geofence altitude mode - Select which altitude (AMSL) source should be used for geofence calculations. - 0 - 1 - - Autopilot estimator global position altitude (GPS) - Raw barometer altitude (assuming standard atmospheric pressure) - - - - Geofence counter limit - Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered - -1 - 10 - 1 - - - Max horizontal distance in meters - Maximum horizontal distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. - 0 - 10000 - m - 1 - - - Max vertical distance in meters - Maximum vertical distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. - 0 - 10000 - m - 1 - - - Geofence source - Select which position source should be used. Selecting GPS instead of global position makes sure that there is no dependence on the position estimator 0 = global position, 1 = GPS + + Throttle at min airspeed + Required throttle for level flight at minimum airspeed FW_AIRSPD_MIN (sea level, standard atmosphere) Set to 0 to disable mapping of airspeed to trim throttle below FW_AIRSPD_TRIM. 0 1 - - GPOS - GPS - + 2 + 0.01 - - - - Gate size for acceleration fusion - Sets the number of standard deviations used by the innovation consistency test. - 1.0 - 10.0 - SD - 1 + + Idle throttle + This is the minimum throttle while on the ground For aircraft with internal combustion engines, this parameter should be set above the desired idle rpm. For electric motors, idle should typically be set to zero. Note that in automatic modes, "landed" conditions will engage idle throttle. + 0.0 + 0.4 + norm + 2 + 0.01 - - 1-sigma initial hover thrust uncertainty - Sets the number of standard deviations used by the innovation consistency test. + + Throttle limit max + This is the maximum throttle % that can be used by the controller. For overpowered aircraft, this should be reduced to a value that provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX. 0.0 1.0 - normalized_thrust - 3 + norm + 2 + 0.01 - - Hover thrust process noise - Reduce to make the hover thrust estimate more stable, increase if the real hover thrust is expected to change quickly over time. - 0.0001 + + Throttle limit min + This is the minimum throttle % that can be used by the controller. For electric aircraft this will normally be set to zero, but can be set to a small non-zero value if a folding prop is fitted to prevent the prop from folding and unfolding repeatedly in-flight or to provide some aerodynamic drag from a turning prop to improve the descent rate. For aircraft with internal combustion engine this parameter should be set for desired idle rpm. + 0.0 1.0 - normalized_thrust/s - 4 + norm + 2 + 0.01 - - - - Serial Configuration for Iridium (with MAVLink) - Configure on which serial port to run Iridium (with MAVLink). - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - + + Throttle max slew rate + Maximum slew rate for the commanded throttle + 0.0 + 1.0 + 2 + 0.01 - - Satellite radio read interval. Only required to be nonzero if data is not sent using a ring call - 0 - 5000 - s + + Trim throttle + This is the throttle setting required to achieve FW_AIRSPD_TRIM during level flight. + 0.0 + 1.0 + norm + 2 + 0.01 - - Iridium SBD session timeout - 0 - 300 - s + + Takeoff Airspeed + The calibrated airspeed setpoint TECS will stabilize to during the takeoff climbout. If set <= 0.0, FW_AIRSPD_MIN will be set by default. + -1.0 + m/s + 1 + 0.1 - - Time the Iridium driver will wait for additional mavlink messages to combine them into one SBD message - Value 0 turns the functionality off - 0 - 500 - ms + + Altitude error time constant + 2.0 + 2 + 0.5 - - - - Airspeed max - Maximum airspeed allowed in the landed state - 4 - 20 + + Maximum climb rate + This is the maximum climb rate that the aircraft can achieve with the throttle set to THR_MAX and the airspeed set to the trim value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced. + 1.0 + 15.0 m/s 1 + 0.5 - - Fixedwing max horizontal velocity - Maximum horizontal velocity allowed in the landed state + + Default target climbrate + The default rate at which the vehicle will climb in autonomous modes to achieve altitude setpoints. In manual modes this defines the maximum rate at which the altitude setpoint can be increased. 0.5 - 10 + 15 m/s - 1 + 2 + 0.01 - - Fixedwing max climb rate - Maximum vertical velocity allowed in the landed state - 0.1 - 20 - m/s - 1 + + Height rate feed forward + 0.0 + 1.0 + 2 + 0.05 - - Fixedwing max horizontal acceleration - Maximum horizontal (x,y body axes) acceleration allowed in the landed state - 2 - 15 - m/s^2 - 1 + + Integrator gain pitch + This is the integrator gain on the pitch part of the control loop. Increasing this gain increases the speed at which speed and height offsets are trimmed out, but reduces damping and increases overshoot. Set this value to zero to completely disable all integrator action. + 0.0 + 2.0 + 2 + 0.05 - - Ground effect altitude for multicopters - The height above ground below which ground effect creates barometric altitude errors. A negative value indicates no ground effect. - -1 - m + + Integrator gain throttle + This is the integrator gain on the throttle part of the control loop. Increasing this gain increases the speed at which speed and height offsets are trimmed out, but reduces damping and increases overshoot. Set this value to zero to completely disable all integrator action. + 0.0 + 2.0 2 + 0.05 - - Maximum altitude for multicopters - The system will obey this limit as a hard altitude limit. This setting will be consolidated with the GF_MAX_VER_DIST parameter. A negative value indicates no altitude limitation. - -1 - 10000 - m + + Pitch damping factor + This is the damping gain for the pitch demand loop. Increase to add damping to correct for oscillations in height. The default value of 0.0 will work well provided the pitch to servo controller has been tuned properly. + 0.0 + 2.0 2 + 0.1 - - Multicopter max rotation - Maximum allowed angular velocity around each axis allowed in the landed state. - deg/s + + Roll -> Throttle feedforward + Increasing this gain turn increases the amount of throttle that will be used to compensate for the additional drag created by turning. Ideally this should be set to approximately 10 x the extra sink rate in m/s created by a 45 degree bank turn. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns. Efficient high aspect-ratio aircraft (eg powered sailplanes) can use a lower value, whereas inefficient low aspect-ratio models (eg delta wings) can use a higher value. + 0.0 + 20.0 1 + 0.5 - - Multicopter land detection trigger time - Total time it takes to go through all three land detection stages: ground contact, maybe landed, landed when all necessary conditions are constantly met. - 0.1 - 10.0 - s - 1 + + Specific total energy balance rate feedforward gain + 0.5 + 3 + 2 + 0.01 - - Multicopter max horizontal velocity - Maximum horizontal velocity allowed in the landed state + + Maximum descent rate + This sets the maximum descent rate that the controller will use. If this value is too large, the aircraft can over-speed on descent. This should be set to a value that can be achieved without exceeding the lower pitch angle limit and without over-speeding the aircraft. + 1.0 + 15.0 m/s 1 + 0.5 - - Multicopter max climb rate - Maximum vertical velocity allowed in the landed state + + Minimum descent rate + This is the sink rate of the aircraft with the throttle set to THR_MIN and flown at the same airspeed as used to measure FW_T_CLMB_MAX. + 1.0 + 5.0 m/s 1 + 0.5 - - Total flight time in microseconds - Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. - 0 + + Default target sinkrate + The default rate at which the vehicle will sink in autonomous modes to achieve altitude setpoints. In manual modes this defines the maximum rate at which the altitude setpoint can be decreased. + 0.5 + 15 + m/s + 2 + 0.01 - - Total flight time in microseconds - Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. - 0 + + Speed <--> Altitude priority + This parameter adjusts the amount of weighting that the pitch control applies to speed vs height errors. Setting it to 0.0 will cause the pitch control to control height and ignore speed errors. This will normally improve height accuracy but give larger airspeed errors. Setting it to 2.0 will cause the pitch control loop to control speed and ignore height errors. This will normally reduce airspeed errors, but give larger height errors. The default value of 1.0 allows the pitch control to simultaneously control height and speed. Set to 2 for gliders. + 0.0 + 2.0 + 1 + 1.0 - - - - Acceleration uncertainty - Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection + + Airspeed rate measurement standard deviation for airspeed filter + This is the measurement standard deviation for the airspeed rate used in the airspeed filter in TECS. 0.01 - (m/s^2)^2 + 10.0 + m/s^2 2 + 0.1 - - Landing target measurement uncertainty - Variance of the landing target measurement from the driver. Higher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements. - tan(rad)^2 - 4 - - - Landing target mode - Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation. - 0 - 1 - - Moving - Stationary - - - - Initial landing target position uncertainty - Initial variance of the relative landing target position in x and y direction - 0.001 - m^2 - 3 - - - Scale factor for sensor measurements in sensor x axis - Landing target x measurements are scaled by this factor before being used + + Process noise standard deviation for the airspeed rate in the airspeed filter + This is the process noise standard deviation in the airspeed filter filter defining the noise in the airspeed rate for the constant airspeed rate model. This is used to define how much the airspeed and the airspeed rate are filtered. The smaller the value the more the measurements are smoothed with the drawback for delays. 0.01 - 3 + 10.0 + m/s^2 + 2 + 0.1 - - Scale factor for sensor measurements in sensor y axis - Landing target y measurements are scaled by this factor before being used + + Airspeed measurement standard deviation for airspeed filter + This is the measurement standard deviation for the airspeed used in the airspeed filter in TECS. 0.01 - 3 - - - Initial landing target velocity uncertainty - Initial variance of the relative landing target velocity in x and y directions - 0.001 - (m/s)^2 - 3 - - - - - Accelerometer xy noise density - Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error. - 0.00001 - 2 - m/s^2/sqrt(Hz) - 4 + 10.0 + m/s + 2 + 0.1 - - Accelerometer z noise density - Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) - 0.00001 + + Specific total energy rate first order filter time constant + This filter is applied to the specific total energy rate used for throttle damping. + 0.0 2 - m/s^2/sqrt(Hz) - 4 + 2 + 0.01 - - Barometric presssure altitude z standard deviation - 0.01 - 100 - m + + True airspeed error time constant + 2.0 2 + 0.5 - - Max EPH allowed for GPS initialization - 1.0 - 5.0 - m - 3 + + Throttle damping factor + This is the damping gain for the throttle demand loop. Increase to add damping to correct for oscillations in speed and height. + 0.0 + 2.0 + 2 + 0.1 - - Max EPV allowed for GPS initialization + + Maximum vertical acceleration + This is the maximum vertical acceleration (in m/s/s) either up or down that the controller will use to correct speed or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) allows for reasonably aggressive pitch changes if required to recover from under-speed conditions. 1.0 - 5.0 - m - 3 + 10.0 + m/s^2 + 1 + 0.5 - - Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow) - By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable + + Wind-based airspeed scaling factor + Multiplying this factor with the current absolute wind estimate gives the airspeed offset added to the minimum airspeed setpoint limit. This helps to make the system more robust against disturbances (turbulence) in high wind. Only applies to AUTO flight mode. airspeed_min_adjusted = FW_AIRSPD_MIN + FW_WIND_ARSP_SC * wind.length() 0 - 1 + 2 + 0.01 - - Flow gyro high pass filter cut off frequency - 0 - 2 - Hz - 3 + + + + Enable Actuator Failure check + If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle level is being consumed. Otherwise this indicates an motor failure. + true - - Optical flow z offset from center - -1 - 1 - m - 3 + + Motor Failure Current/Throttle Threshold + Motor failure triggers only below this current value + 0.0 + 50.0 + A/% + 2 + 1 - - Optical flow minimum quality threshold - 0 - 255 - 0 + + Motor Failure Throttle Threshold + Motor failure triggers only above this throttle value. + 0.0 + 1.0 + norm + 2 + 0.01 - - Optical flow rotation (roll/pitch) noise gain - 0.1 - 10.0 - m/s/rad - 3 + + Motor Failure Time Threshold + Motor failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time. + 10 + 10000 + ms + 100 - - Optical flow angular velocity noise gain - 0.0 - 10.0 - m/rad - 3 + + Enable checks on ESCs that report their arming state + If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle. - - Optical flow scale - 0.1 - 10.0 - m - 3 + + Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS) + Enabled on either AUX5 or MAIN5 depending on board. External ATS is required by ASTM F3322-18. + true - - Integer bitmask controlling data fusion - Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector) - 0 - 255 - - fuse GPS, requires GPS for alt. init - fuse optical flow - fuse vision position - fuse landing target - fuse land detector - pub agl as lpos down - flow gyro compensation - fuse baro - + + The PWM threshold from external automatic trigger system for engaging failsafe + External ATS is required by ASTM F3322-18. + us + 2 - - GPS delay compensaton + + FailureDetector Max Pitch + Maximum pitch angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check 0 - 0.4 + 180 + deg + + + Pitch failure trigger time + Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure. + 0.02 + 5 s 2 - - GPS xy velocity standard deviation - EPV used if greater than this value. - 0.01 - 2 - m/s - 3 - - - GPS z velocity standard deviation - 0.01 - 2 - m/s - 3 + + FailureDetector Max Roll + Maximum roll angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check + 0 + 180 + deg - - Minimum GPS xy standard deviation, uses reported EPH if greater - 0.01 + + Roll failure trigger time + Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure. + 0.02 5 - m + s 2 - - Minimum GPS z standard deviation, uses reported EPV if greater - 0.01 - 200 - m - 2 + + Imbalanced propeller check threshold + Value at which the imbalanced propeller metric (based on horizontal and vertical acceleration variance) triggers a failure Setting this value to 0 disables the feature. + 0 + 1000 + 1 - - Land detector xy velocity standard deviation - 0.01 - 10.0 - m/s - 3 - - - Land detector z standard deviation - 0.001 - 10.0 + + + + Maximum radius of orbit + 1.0 + 10000.0 m - 3 + 1 + 0.5 - - Local origin latitude for nav w/o GPS - -90 - 90 - deg - 8 + + + + Altitude control mode + Maintain altitude or track target's altitude. When maintaining the altitude, the drone can crash into terrain when the target moves uphill. When tracking the target's altitude, the follow altitude FLW_TGT_HT should be high enough to prevent terrain collisions due to GPS inaccuracies of the target. + + 2D Tracking: Maintain constant altitude relative to home and track XY position only + 2D + Terrain: Maintain constant altitude relative to terrain below and track XY position + 3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless) + - - Lidar z offset from center of vehicle +down - -1 - 1 + + Distance to follow target from + The distance in meters to follow the target at + 1.0 m - 3 - - Lidar z standard deviation - 0.01 - 1 + + Follow Angle setting in degrees + Angle to follow the target from. 0.0 Equals straight in front of the target's course (direction of motion) and the angle increases in clockwise direction, meaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees Note: When the user force sets the angle out of the min/max range, it will be wrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range. + -180.0 + 180.0 + + + Follow target height + Following height above the target + 8.0 m - 3 - - Local origin longitude for nav w/o GPS - -180 - 180 - deg - 8 + + Maximum tangential velocity setting for generating the follow orbit trajectory + This is the maximum tangential velocity the drone will circle around the target whenever an orbit angle setpoint changes. Higher value means more aggressive follow behavior. + 0.0 + 20.0 + 1 - - Minimum landing target standard covariance, uses reported covariance if greater + + Responsiveness to target movement in Target Estimator + lower values increase the responsiveness to changing position, but also ignore less noise 0.0 - 10 - m^2 + 1.0 2 - - Accel bias propagation noise density + + + + GNSS Systems for Primary GPS (integer bitmask) + This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS 0 - 1 - m/s^3/sqrt(Hz) - 8 + 31 + true + + GPS (with QZSS) + SBAS + Galileo + BeiDou + GLONASS + - - Position propagation noise density - Increase to trust measurements more. Decrease to trust model more. + + Protocol for Main GPS + Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower. 0 - 1 - m/s/sqrt(Hz) - 8 + 7 + true + + Auto detect + u-blox + MTK + Ashtech / Trimble + Emlid Reach + Femtomes + NMEA (generic) + Septentrio (SBF) + - - Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001) + + GNSS Systems for Secondary GPS (integer bitmask) + This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS 0 - 1 - m/s/sqrt(Hz) - 3 + 31 + true + + GPS (with QZSS) + SBAS + Galileo + BeiDou + GLONASS + - - Velocity propagation noise density - Increase to trust measurements more. Decrease to trust model more. + + Protocol for Secondary GPS + Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower. 0 - 1 - m/s^2/sqrt(Hz) - 8 + 6 + true + + Auto detect + u-blox + MTK + Ashtech / Trimble + Emlid Reach + Femtomes + NMEA (generic) + - - Sonar z offset from center of vehicle +down - -1 - 1 - m - 3 + + Log GPS communication data + If this is set to 1, all GPS communication data will be published via uORB, and written to the log file as gps_dump message. If this is set to 2, the main GPS is configured to output RTCM data, which is then logged as gps_dump and can be used for PPK. + 0 + 2 + + Disable + Full communication + RTCM output (PPK) + - - Sonar z standard deviation - 0.01 - 1 - m + + Pitch offset for dual antenna GPS + Vertical offsets can be compensated for by adjusting the Pitch offset (Septentrio). Note that this can be interpreted as the "roll" angle in case the antennas are aligned along the perpendicular axis. This occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame. Since pitch is defined as the right-handed rotation about the vehicle Y axis, a situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch. + -90 + 90 + deg 3 + true - - Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg) - Used to calculate increased terrain random walk nosie due to movement. + + Enable sat info (if available) + Enable publication of satellite info (ORB_ID(satellite_info)) if possible. Not available on MTK. + true + + + u-blox F9P UART2 Baudrate + Select a baudrate for the F9P's UART2 port. In GPS_UBX_MODE 1, 2, and 3, the F9P's UART2 port is configured to send/receive RTCM corrections. Set this to 57600 if you want to attach a telemetry radio on UART2. 0 - 100 - % - 3 + B/s + true - - Vicon position standard deviation - 0.0001 - 1 - m - 4 + + u-blox protocol configuration for interfaces + 0 + 32 + true + + Enable I2C input protocol UBX + Enable I2C input protocol NMEA + Enable I2C input protocol RTCM3X + Enable I2C output protocol UBX + Enable I2C output protocol NMEA + Enable I2C output protocol RTCM3X + - - Vision delay compensation - Set to zero to enable automatic compensation from measurement timestamps + + u-blox GPS dynamic platform model + u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment. 0 - 0.1 - s - 2 + 9 + true + + stationary + automotive + airborne with <1g acceleration + airborne with <2g acceleration + airborne with <4g acceleration + - - Vision xy standard deviation - 0.01 + + u-blox GPS Mode + Select the u-blox configuration setup. Most setups will use the default, including RTK and dual GPS without heading. If rover has RTCM corrections from a static base (or other static correction source) coming in on UART2, then select Mode 5. The Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output heading information, whereas the secondary will act as moving base. Modes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the F9P units are connected to each other. Modes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required. RTK is still possible with this setup. + 0 1 - m - 3 - - - Vision z standard deviation - 0.01 - 100 - m - 3 + true + + Default + Heading (Rover With Moving Base UART1 Connected To Autopilot, UART2 Connected To Moving Base) + Moving Base (UART1 Connected To Autopilot, UART2 Connected To Rover) + Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600) + Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600) + Rover with Static Base on UART2 (similar to Default, except coming in on UART2) + - - Required velocity xy standard deviation to publish position - 0.01 - 1.0 - m/s + + Heading/Yaw offset for dual antenna GPS + Heading offset angle for dual antenna GPS setups that support heading estimation. Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the rover (or Unicore primary) antenna is in front. The offset angle increases clockwise. Set this to 90 if the rover (or Unicore primary) antenna is placed on the right side of the vehicle and the moving base antenna is on the left side. (Note: the Unicore primary antenna is the one connected on the right as seen from the top). + 0 + 360 + deg 3 + true - - Cut frequency for state publication - 5 - 1000 - Hz - 0 - - - Required z standard deviation to publish altitude/ terrain - 0.3 - 5.0 - m - 1 + + PPS Capture Enable + Enables the PPS capture module. This switches mode of FMU channel 7 to be the PPS input channel. + true - - - Broadcast heartbeats on local network for MAVLink instance 0 - This allows a ground control station to automatically find the drone on the local network. + + + Geofence violation action + Note: Setting this value to 4 enables flight termination, which will kill the vehicle on violation of the fence. + 0 + 5 - Never broadcast - Always broadcast - Only multicast + None + Warning + Hold mode + Return mode + Terminate + Land mode - - Serial Configuration for MAVLink (instance 0) - Configure on which serial port to run MAVLink. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - Ethernet - - - - Enable MAVLink Message forwarding for instance 0 - If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). - True - - - MAVLink Mode for instance 0 - The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates. - True - - Normal - Custom - Onboard - OSD - Magic - Config - Minimal - External Vision - Gimbal - Onboard Low Bandwidth - - - - Enable software throttling of mavlink on instance 0 - If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS. - True - - - Maximum MAVLink sending rate for instance 0 - Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links). + + Geofence altitude mode + Select which altitude (AMSL) source should be used for geofence calculations. 0 - B/s - True - - - MAVLink Remote Port for instance 0 - If ethernet enabled and selected as configuration for MAVLink instance 0, selected remote port will be set and used in MAVLink instance 0. - True - - - MAVLink Network Port for instance 0 - If ethernet enabled and selected as configuration for MAVLink instance 0, selected udp port will be set and used in MAVLink instance 0. - True - - - Broadcast heartbeats on local network for MAVLink instance 1 - This allows a ground control station to automatically find the drone on the local network. + 1 - Never broadcast - Always broadcast - Only multicast + Autopilot estimator global position altitude (GPS) + Raw barometer altitude (assuming standard atmospheric pressure) - - Serial Configuration for MAVLink (instance 1) - Configure on which serial port to run MAVLink. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - Ethernet - - - - Enable MAVLink Message forwarding for instance 1 - If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). - True - - - MAVLink Mode for instance 1 - The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates. - True - - Normal - Custom - Onboard - OSD - Magic - Config - Minimal - External Vision - Gimbal - Onboard Low Bandwidth - - - - Enable software throttling of mavlink on instance 1 - If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS. - True - - - Maximum MAVLink sending rate for instance 1 - Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links). + + Geofence counter limit + Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered + -1 + 10 + 1 + + + Max horizontal distance in meters + Maximum horizontal distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. 0 - B/s - True + 10000 + m + 1 - - MAVLink Remote Port for instance 1 - If ethernet enabled and selected as configuration for MAVLink instance 1, selected remote port will be set and used in MAVLink instance 1. - True + + Max vertical distance in meters + Maximum vertical distance in meters the vehicle can be from home before triggering a geofence action. Disabled if 0. + 0 + 10000 + m + 1 - - MAVLink Network Port for instance 1 - If ethernet enabled and selected as configuration for MAVLink instance 1, selected udp port will be set and used in MAVLink instance 1. - True + + [EXPERIMENTAL] Use Pre-emptive geofence triggering + WARNING: This experimental feature may cause flyaways. Use at your own risk. Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory would result in a breach happening before the vehicle can make evasive maneuvers. The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing). - - Broadcast heartbeats on local network for MAVLink instance 2 - This allows a ground control station to automatically find the drone on the local network. + + Geofence source + Select which position source should be used. Selecting GPS instead of global position makes sure that there is no dependence on the position estimator 0 = global position, 1 = GPS + 0 + 1 - Never broadcast - Always broadcast - Only multicast + GPOS + GPS - - Serial Configuration for MAVLink (instance 2) - Configure on which serial port to run MAVLink. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - Ethernet - - - - Enable MAVLink Message forwarding for instance 2 - If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). - True - - - MAVLink Mode for instance 2 - The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates. - True - - Normal - Custom - Onboard - OSD - Magic - Config - Minimal - External Vision - Gimbal - Onboard Low Bandwidth - - - - Enable software throttling of mavlink on instance 2 - If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS. - True - - - Maximum MAVLink sending rate for instance 2 - Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links). - 0 - B/s - True - - - MAVLink Remote Port for instance 2 - If ethernet enabled and selected as configuration for MAVLink instance 2, selected remote port will be set and used in MAVLink instance 2. - True - - - MAVLink Network Port for instance 2 - If ethernet enabled and selected as configuration for MAVLink instance 2, selected udp port will be set and used in MAVLink instance 2. - True + + + + Gate size for acceleration fusion + Sets the number of standard deviations used by the innovation consistency test. + 1.0 + 10.0 + SD + 1 - - MAVLink component ID - 1 - 250 - true + + 1-sigma initial hover thrust uncertainty + Sets the number of standard deviations used by the innovation consistency test. + 0.0 + 1.0 + normalized_thrust + 3 - - Forward external setpoint messages - If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode + + Hover thrust process noise + Reduce to make the hover thrust estimate more stable, increase if the real hover thrust is expected to change quickly over time. + 0.0001 + 1.0 + normalized_thrust/s + 4 - - Parameter hash check - Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously. + + Max deviation from MPC_THR_HOVER + Defines the range of the hover thrust estimate around MPC_THR_HOVER. A value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7]. Set to a large value if the vehicle operates in varying physical conditions that affect the required hover thrust strongly (e.g. differently sized payloads). + 0.01 + 0.4 + normalized_thrust + 2 - - Hearbeat message forwarding - The 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. + + Horizontal velocity threshold for sensitivity reduction + Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles with large lifting surfaces. + 1.0 + 20.0 + m/s + 1 - - 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. + + Vertical velocity threshold for sensitivity reduction + Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles affected by air drag when climbing or descending. + 1.0 + 10.0 + m/s + 1 - - MAVLink protocol version - - Default to 1, switch to 2 if GCS sends version 2 - Always use version 1 - Always use version 2 - + + + + Satellite radio read interval. Only required to be nonzero if data is not sent using a ring call + 0 + 5000 + s - - Timeout in seconds for the RADIO_STATUS reports coming in - If the connected radio stops reporting RADIO_STATUS for a certain time, a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow control is reset. - 1 - 250 + + Iridium SBD session timeout + 0 + 300 s - - MAVLink SiK Radio ID - When non-zero the MAVLink app will attempt to configure the SiK radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults. Only applies if this mavlink instance is going through a SiK radio - -1 - 240 + + Time the Iridium driver will wait for additional mavlink messages to combine them into one SBD message + Value 0 turns the functionality off + 0 + 500 + ms - - MAVLink system ID - 1 - 250 - true + + + + Fixed-wing land detector: Max airspeed + Maximum airspeed allowed in the landed state + 2 + 20 + m/s + 1 - - MAVLink airframe type - 1 - 27 - - Generic micro air vehicle - Fixed wing aircraft - Quadrotor - Coaxial helicopter - Normal helicopter with tail rotor - Ground installation - Operator control unit / ground control station - Airship, controlled - Free balloon, uncontrolled - Rocket - Ground rover - Surface vessel, boat, ship - Submarine - Hexarotor - Octorotor - Tricopter - Flapping wing - Kite - Onboard companion controller - Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. - Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. - Tiltrotor VTOL - VTOL reserved 2 - VTOL reserved 3 - VTOL reserved 4 - VTOL reserved 5 - Onboard gimbal - Onboard ADSB peripheral - + + Fixed-wing land detection trigger time + Time the land conditions (speeds and acceleration) have to be satisfied to detect a landing. + 0.1 + s + 1 + true - - Use/Accept HIL GPS message even if not in HIL mode - If set to 1 incoming HIL GPS messages are parsed. + + Fixed-wing land detector: Max horizontal velocity threshold + Maximum horizontal velocity allowed in the landed state. A factor of 0.7 is applied in case of airspeed-less flying (either because no sensor is present or sensor data got invalid in flight). + 0.5 + 10 + m/s + 1 - - - - Maximal horizontal distance from home to first waypoint - Failsafe check to prevent running mission stored from previous flight at a new takeoff location. Set a value of zero or less to disable. The mission will not be started if the current waypoint is more distant than MIS_DIST_1WP from the home position. - 0 - 10000 - m + + Fixed-wing land detector: Max vertiacal velocity threshold + Maximum vertical velocity allowed in the landed state. + 0.1 + 20 + m/s 1 - 100 - - Maximal horizontal distance between waypoint - Failsafe check to prevent running missions which are way too big. Set a value of zero or less to disable. The mission will not be started if any distance between two subsequent waypoints is greater than MIS_DIST_WPS. - 0 - 10000 - m + + Fixed-wing land detector: Max horizontal acceleration + Maximum horizontal (x,y body axes) acceleration allowed in the landed state + 2 + 15 + m/s^2 1 - 100 - - Minimum Loiter altitude - This is the minimum altitude the system will always obey. The intent is to stay out of ground effect. set to -1, if there shouldn't be a minimum loiter altitude + + Ground effect altitude for multicopters + The height above ground below which ground effect creates barometric altitude errors. A negative value indicates no ground effect. -1 - 80 m - 1 - 0.5 - - - Enable yaw control of the mount. (Only affects multicopters and ROI mission items) - If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. If disabled, the vehicle will yaw towards the ROI. - 0 - 1 - - Disable - Enable - + 2 - - Take-off altitude - This is the minimum altitude the system will take off to. - 0 - 80 + + Maximum altitude for multicopters + The system will obey this limit as a hard altitude limit. This setting will be consolidated with the GF_MAX_VER_DIST parameter. A negative value indicates no altitude limitation. + -1 + 10000 m - 1 - 0.5 - - - Take-off waypoint required - If set, the mission feasibility checker will check for a takeoff waypoint on the mission. + 2 - - Max yaw error in degrees needed for waypoint heading acceptance - 0 - 90 - deg + + Multicopter max rotation + Maximum allowed angular velocity around each axis allowed in the landed state. + deg/s 1 - 1 - - Time in seconds we wait on reaching target heading at a waypoint if it is forced - If set > 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default. - -1 - 20 + + Multicopter land detection trigger time + Total time it takes to go through all three land detection stages: ground contact, maybe landed, landed when all necessary conditions are constantly met. + 0.1 + 10.0 s 1 - 1 - - Yaw mode - Specifies the heading in Auto. + + Multicopter max horizontal velocity + Maximum horizontal velocity allowed in the landed state + m/s + 1 + + + Multicopter vertical velocity threshold + Vertical velocity threshold to detect landing. Has to be set lower than the expected minimal speed for landing, which is either MPC_LAND_SPEED or MPC_LAND_CRWL. This is enforced by an automatic check. 0 - 4 - - towards waypoint - towards home - away from home - along trajectory - towards waypoint (yaw first) - + m/s + 2 - - Acceptance Radius - Default acceptance radius, overridden by acceptance radius of waypoint if set. For fixed wing the L1 turning distance is used for horizontal acceptance. - 0.05 - 200.0 - m - 1 - 0.5 - - - Force VTOL mode takeoff and land - - - FW Altitude Acceptance Radius before a landing - Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller than the standard vertical acceptance because close to the ground higher accuracy is required. - 0.05 - 200.0 - m - 1 + + Total flight time in microseconds + Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. + 0 - - FW Altitude Acceptance Radius - Acceptance radius for fixedwing altitude. - 0.05 - 200.0 - m - 1 - 0.5 + + Total flight time in microseconds + Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. + 0 - - Loiter radius (FW only) - Default value of loiter radius for missions, Hold mode, Return mode, etc. (fixedwing only). - 25 - 1000 - m - 1 - 0.5 + + + + Acceleration uncertainty + Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection + 0.01 + (m/s^2)^2 + 2 - - MC Altitude Acceptance Radius - Acceptance radius for multicopter altitude. - 0.05 - 200.0 - m - 1 - 0.5 + + Landing target measurement uncertainty + Variance of the landing target measurement from the driver. Higher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements. + tan(rad)^2 + 4 - - Set traffic avoidance mode - Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders + + Landing target mode + Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation. + 0 + 1 - Disabled - Warn only - Return mode - Land mode - Position Hold mode + Moving + Stationary - - Set NAV TRAFFIC AVOID RADIUS MANNED - Defines the Radius where NAV TRAFFIC AVOID is Called For Manned Aviation - 500 + + Initial landing target position uncertainty + Initial variance of the relative landing target position in x and y direction + 0.001 + m^2 + 3 + + + Scale factor for sensor measurements in sensor x axis + Landing target x measurements are scaled by this factor before being used + 0.01 + 3 + + + Scale factor for sensor measurements in sensor y axis + Landing target y measurements are scaled by this factor before being used + 0.01 + 3 + + + X Position of IRLOCK in body frame (forward) m + 3 + true - - Set NAV TRAFFIC AVOID RADIUS - Defines the Radius where NAV TRAFFIC AVOID is Called For Unmanned Aviation - 10 - 500 + + Y Position of IRLOCK in body frame (right) m + 3 + true - - - - 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 (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 - + + Z Position of IRLOCK in body frame (downward) + m + 3 + true - - Motor Ordering - Determines the motor ordering. This can be used for example in combination with a 4-in-1 ESC that assumes a motor ordering which is different from PX4. ONLY supported for Quads. When changing this, make sure to test the motor response without props first. + + Rotation of IRLOCK sensor relative to airframe + Default orientation of Yaw 90° + -1 + 40 + true - PX4 - Betaflight / Cleanflight + No rotation + Yaw 45° + Yaw 90° + Yaw 135° + Yaw 180° + Yaw 225° + Yaw 270° + Yaw 315° + + Initial landing target velocity uncertainty + Initial variance of the relative landing target velocity in x and y directions + 0.001 + (m/s)^2 + 3 + - - - Stabilize the mount - Set to true for servo gimbal, false for passthrough. This is required for a gimbal which is not capable of stabilizing itself and relies on the IMU's attitude estimation. - 0 + + + Accelerometer xy noise density + Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error. + 0.00001 2 - - Disable - Stabilize all axis - Stabilize yaw for absolute/lock mode. - - - - Auxiliary channel to control pitch (in AUX input or manual mode) - 0 - 6 - - Disable - AUX1 - AUX2 - AUX3 - AUX4 - AUX5 - AUX6 - + m/s^2/sqrt(Hz) + 4 - - Auxiliary channel to control roll (in AUX input or manual mode) - 0 - 6 - - Disable - AUX1 - AUX2 - AUX3 - AUX4 - AUX5 - AUX6 - + + Accelerometer z noise density + Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) + 0.00001 + 2 + m/s^2/sqrt(Hz) + 4 - - Auxiliary channel to control yaw (in AUX input or manual mode) - 0 - 6 - - Disable - AUX1 - AUX2 - AUX3 - AUX4 - AUX5 - AUX6 - + + Barometric presssure altitude z standard deviation + 0.01 + 100 + m + 2 - - Mavlink Component ID of the mount - If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID. + + Max EPH allowed for GPS initialization + 1.0 + 5.0 + m + 3 - - Mavlink System ID of the mount - If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID. + + Max EPV allowed for GPS initialization + 1.0 + 5.0 + m + 3 - - Mount input mode - RC uses the AUX input channels (see MNT_MAN_* parameters), MAVLINK_ROI uses the MAV_CMD_DO_SET_ROI Mavlink message, and MAVLINK_DO_MOUNT the MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL messages to control a mount. - -1 - 4 - true - - DISABLED - AUTO - RC - MAVLINK_ROI (protocol v1) - MAVLINK_DO_MOUNT (protocol v1) - MAVlink gimbal protocol v2 - + + Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow) + By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable + 0 + 1 - - Mount output mode - AUX uses the mixer output Control Group #2. MAVLINK uses the MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL MavLink messages to control a mount (set MNT_MAV_SYSID & MNT_MAV_COMPID) + + Flow gyro high pass filter cut off frequency 0 2 - - AUX - MAVLink gimbal protocol v1 - MAVLink gimbal protocol v2 - - - - Mixer value for selecting a locking mode - if required for the gimbal (only in AUX output mode) - -1.0 - 1.0 + Hz 3 - - Mixer value for selecting normal mode - if required by the gimbal (only in AUX output mode) - -1.0 - 1.0 + + Optical flow z offset from center + -1 + 1 + m 3 - - Offset for pitch channel output in degrees - -360.0 - 360.0 - 1 - - - Offset for roll channel output in degrees - -360.0 - 360.0 - 1 - - - Offset for yaw channel output in degrees - -360.0 - 360.0 - 1 - - - Range of pitch channel output in degrees (only in AUX output mode) - 1.0 - 720.0 - 1 - - - Range of roll channel output in degrees (only in AUX output mode) - 1.0 - 720.0 - 1 - - - Range of yaw channel output in degrees (only in AUX output mode) - 1.0 - 720.0 - 1 - - - Angular pitch rate for manual input in degrees/second - Full stick input [-1..1] translats to [-pitch rate..pitch rate]. - 1.0 - 90.0 + + Optical flow minimum quality threshold + 0 + 255 - - Angular yaw rate for manual input in degrees/second - Full stick input [-1..1] translats to [-yaw rate..yaw rate]. - 1.0 - 90.0 + + Optical flow rotation (roll/pitch) noise gain + 0.1 + 10.0 + m/s/rad + 3 - - - - Max pitch rate - Limit for pitch rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro. + + Optical flow angular velocity noise gain 0.0 - 1800.0 - deg/s - 1 - 5 + 10.0 + m/rad + 3 - - Pitch P gain - Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad. - 0.0 - 12 - 2 - 0.1 + + Optical flow scale + 0.1 + 10.0 + m + 3 - - Max roll rate - Limit for roll rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro. - 0.0 - 1800.0 - deg/s - 1 - 5 + + Integer bitmask controlling data fusion + Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector) + 0 + 255 + + fuse GPS, requires GPS for alt. init + fuse optical flow + fuse vision position + fuse landing target + fuse land detector + pub agl as lpos down + flow gyro compensation + fuse baro + - - Roll P gain - Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. - 0.0 - 12 + + GPS delay compensaton + 0 + 0.4 + s 2 - 0.1 - - Max yaw rate - 0.0 - 1800.0 - deg/s - 1 - 5 + + GPS xy velocity standard deviation + EPV used if greater than this value. + 0.01 + 2 + m/s + 3 - - Yaw P gain - Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad. - 0.0 + + GPS z velocity standard deviation + 0.01 + 2 + m/s + 3 + + + Minimum GPS xy standard deviation, uses reported EPH if greater + 0.01 5 + m 2 - 0.1 - - Yaw weight - A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. Deprioritizing yaw is necessary because multicopters have much less control authority in yaw compared to the other axes and it makes sense because yaw is not critical for stable hovering or 3D navigation. For yaw control tuning use MC_YAW_P. This ratio has no inpact on the yaw gain. - 0.0 - 1.0 + + Minimum GPS z standard deviation, uses reported EPV if greater + 0.01 + 200 + m 2 - 0.1 - - Max yaw rate in auto mode - Limit the rate of change of the yaw setpoint in autonomous mode to avoid large control output and mixer saturation. - 0.0 - 360.0 - deg/s - 1 - 5 + + Land detector xy velocity standard deviation + 0.01 + 10.0 + m/s + 3 - - - - Average delay of the range sensor message plus the tracking delay of the position controller in seconds - Only used in Position mode. - 0 - 1 - s + + Land detector z standard deviation + 0.001 + 10.0 + m + 3 - - Minimum distance the vehicle should keep to all obstacles - Only used in Position mode. Collision avoidance is disabled by setting this parameter to a negative value + + Local origin latitude for nav w/o GPS + -90 + 90 + deg + 8 + + + Lidar z offset from center of vehicle +down -1 - 15 + 1 m + 3 - - Boolean to allow moving into directions where there is no sensor data (outside FOV) - Only used in Position mode. + + Lidar z standard deviation + 0.01 + 1 + m + 3 - - Angle left/right from the commanded setpoint by which the collision prevention algorithm can choose to change the setpoint direction - Only used in Position mode. - 0 - 90 + + Local origin longitude for nav w/o GPS + -180 + 180 deg + 8 - - Manual tilt input filter time constant - Setting this parameter to 0 disables the filter + + Minimum landing target standard covariance, uses reported covariance if greater 0.0 - 2.0 - s + 10 + m^2 2 - - Maximum vertical acceleration in velocity controlled modes down - 2.0 - 15.0 - m/s^2 - 2 - 1 + + Accel bias propagation noise density + 0 + 1 + m/s^3/sqrt(Hz) + 8 - - Acceleration for auto and for manual - Note: In manual, this parameter is only used in MPC_POS_MODE 4. - 2.0 - 15.0 - m/s^2 - 2 - 1 + + Position propagation noise density + Increase to trust measurements more. Decrease to trust model more. + 0 + 1 + m/s/sqrt(Hz) + 8 - - Maximum horizontal acceleration for auto mode and for manual mode - MPC_POS_MODE 1 just deceleration 3 acceleration and deceleration 4 just acceleration - 2.0 - 15.0 - m/s^2 - 2 - 1 + + Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001) + 0 + 1 + m/s/sqrt(Hz) + 3 - - Maximum vertical acceleration in velocity controlled modes upward - 2.0 - 15.0 - m/s^2 - 2 - 1 - - - Altitude control mode - Set to 0 to control height relative to the earth frame origin. This origin may move up and down in flight due to sensor drift. Set to 1 to control height relative to estimated distance to ground. The vehicle will move up and down with terrain height variation. Requires a distance to ground sensor. The height controller will revert to using height above origin if the distance to ground estimate becomes invalid as indicated by the local_position.distance_bottom_valid message being false. Set to 2 to control height relative to ground (requires a distance sensor) when stationary and relative to earth frame origin when moving horizontally. The speed threshold is controlled by the MPC_HOLD_MAX_XY parameter. + + Velocity propagation noise density + Increase to trust measurements more. Decrease to trust model more. 0 - 2 - - Altitude following - Terrain following - Terrain hold - + 1 + m/s^2/sqrt(Hz) + 8 - - Deadzone of sticks where position hold is enabled - 0.0 - 1.0 - 2 + + Sonar z offset from center of vehicle +down + -1 + 1 + m + 3 - - Maximum horizontal velocity for which position hold is enabled (use 0 to disable check) - 0.0 - 3.0 - m/s - 2 + + Sonar z standard deviation + 0.01 + 1 + m + 3 - - Maximum vertical velocity for which position hold is enabled (use 0 to disable check) - 0.0 - 3.0 - m/s - 2 + + Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg) + Used to calculate increased terrain random walk nosie due to movement. + 0 + 100 + % + 3 - - Jerk limit in auto mode - Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions, but it also limits its agility. - 1.0 - 80.0 - m/s^3 - 1 - 1 + + Vicon position standard deviation + 0.0001 + 1 + m + 4 - - Maximum jerk limit - Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions, but it also limits its agility (how fast it can change directions or break). Setting this to the maximum value essentially disables the limit. Note: This is only used when MPC_POS_MODE is set to a smoothing mode 3 or 4. - 0.5 - 500.0 - m/s^3 + + Vision delay compensation + Set to zero to enable automatic compensation from measurement timestamps + 0 + 0.1 + s 2 - 1 - - Altitude for 1. step of slow landing (descend) - Below this altitude descending velocity gets limited to a value between "MPC_Z_VEL_MAX_DN" and "MPC_LAND_SPEED" Value needs to be higher than "MPC_LAND_ALT2" - 0 - 122 + + Vision xy standard deviation + 0.01 + 1 m - 1 + 3 - - Altitude for 2. step of slow landing (landing) - Below this altitude descending velocity gets limited to "MPC_LAND_SPEED". Value needs to be lower than "MPC_LAND_ALT1" - 0 - 122 + + Vision z standard deviation + 0.01 + 100 m - 1 + 3 - - Landing descend rate - 0.6 + + Required velocity xy standard deviation to publish position + 0.01 + 1.0 m/s - 1 + 3 - - Minimum manual thrust - Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust. With MC_AIRMODE set to 1, this can safely be set to 0. - 0.0 - 1.0 - norm - 2 - 0.01 + + Cut frequency for state publication + 5 + 1000 + Hz + 0 - - Maximal tilt angle in manual or altitude mode - 0.0 - 90.0 - deg + + Required z standard deviation to publish altitude/ terrain + 0.3 + 5.0 + m 1 - - Max manual yaw rate - 0.0 - 400 - deg/s - 1 + + + + MAVLink component ID + 1 + 250 + true - - Manual yaw rate input filter time constant - Setting this parameter to 0 disables the filter - 0.0 - 5.0 - s - 2 + + Forward external setpoint messages + If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode - - Manual-Position control sub-mode - The supported sub-modes are: 0 Simple position control where sticks map directly to velocity setpoints without smoothing. Useful for velocity control tuning. 3 Smooth position control with maximum acceleration and jerk limits based on jerk optimized trajectory generator (different algorithm than 1). 4 Smooth position control where sticks map to acceleration and there's a virtual brake drag + + Parameter hash check + Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously. + + + Heartbeat message forwarding + The mavlink heartbeat 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. + + + MAVLink protocol version - Simple position control - Smooth position control (Jerk optimized) - Acceleration based input + Default to 1, switch to 2 if GCS sends version 2 + Always use version 1 + Always use version 2 - - Enforced delay between arming and takeoff - For altitude controlled modes the time from arming the motors until a takeoff is possible gets forced to be at least MPC_SPOOLUP_TIME seconds to ensure the motors and propellers can sppol up and reach idle speed before getting commanded to spin faster. This delay is particularly useful for vehicles with slow motor spin-up e.g. because of large propellers. - 0 - 10 + + Timeout in seconds for the RADIO_STATUS reports coming in + If the connected radio stops reporting RADIO_STATUS for a certain time, a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow control is reset. + 1 + 250 s - - Thrust curve in Manual Mode - This parameter defines how the throttle stick input is mapped to commanded thrust in Manual/Stabilized flight mode. In case the default is used ('Rescale to hover thrust'), the stick input is linearly rescaled, such that a centered stick corresponds to the hover throttle (see MPC_THR_HOVER). Select 'No Rescale' to directly map the stick 1:1 to the output. This can be useful in case the hover thrust is very low and the default would lead to too much distortion (e.g. if hover thrust is set to 20%, 80% of the upper thrust range is squeezed into the upper half of the stick range). Note: In case MPC_THR_HOVER is set to 50%, the modes 0 and 1 are the same. + + MAVLink SiK Radio ID + When non-zero the MAVLink app will attempt to configure the SiK radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults. Only applies if this mavlink instance is going through a SiK radio + -1 + 240 + + + MAVLink system ID + 1 + 250 + true + + + MAVLink airframe type + 0 + 22 - Rescale to hover thrust - No Rescale + Generic micro air vehicle + Fixed wing aircraft + Quadrotor + Coaxial helicopter + Normal helicopter with tail rotor + Airship, controlled + Free balloon, uncontrolled + Ground rover + Surface vessel, boat, ship + Submarine + Hexarotor + Octorotor + Tricopter + VTOL Two-rotor Tailsitter + VTOL Quad-rotor Tailsitter + VTOL Tiltrotor + VTOL Standard (separate fixed rotors for hover and cruise flight) + VTOL Tailsitter - - Hover thrust - Vertical thrust required to hover. This value is mapped to center stick for manual throttle control. With this value set to the thrust required to hover, transition from manual to Altitude or Position mode while hovering will occur with the throttle stick near center, which is then interpreted as (near) zero demand for vertical speed. This parameter is also important for the landing detection to work correctly. - 0.1 - 0.8 - norm - 2 - 0.01 + + Use/Accept HIL GPS message even if not in HIL mode + If set to 1 incoming HIL GPS messages are parsed. - - Maximum thrust in auto thrust control - Limit max allowed thrust - 0.0 - 1.0 - norm - 2 - 0.01 + + + + UART ESC baud rate + Default rate is 250Kbps, which is used in off-the-shelf MoadalAI ESC products. + bit/s - - Minimum collective thrust in auto thrust control - It's recommended to set it > 0 to avoid free fall with zero thrust. Note: Without airmode zero thrust leads to zero roll/pitch control authority. (see MC_AIRMODE) - 0.05 - 1.0 - norm - 2 - 0.01 + + UART ESC configuration + Selects what type of UART ESC, if any, is being used. + 0 + 1 + true + + - Disabled + - VOXL ESC + - - Horizontal thrust margin - Margin that is kept for horizontal control when prioritizing vertical thrust. To avoid completely starving horizontal control with high vertical error. - 0.0 - 0.5 - norm - 2 - 0.01 + + UART ESC Mode + Selects what type of mode is enabled, if any + 0 + 2 + true + + - None + - Turtle Mode enabled via AUX1 + - Turtle Mode enabled via AUX2 + - UART Passthrough Mode + - - Maximum tilt angle in air - Limits maximum tilt in AUTO and POSCTRL modes during flight. - 20.0 - 89.0 - deg - 1 + + UART ESC RPM Max + Maximum RPM for ESC + rpm - - Maximum tilt during landing - Limits maximum tilt angle on landing. - 10.0 - 89.0 - deg - 1 + + UART ESC RPM Min + Minimum RPM for ESC + rpm - - Position control smooth takeoff ramp time constant - Increasing this value will make automatic and manual takeoff slower. If it's too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp - 0 - 5 + + UART ESC ID 1 Spin Direction Flag + + - Default + - Reverse + - - Takeoff climb rate - 1 - 5 - m/s - 2 + + UART ESC ID 2 Spin Direction Flag + + - Default + - Reverse + - - Hover thrust source selector - Set false to use the fixed parameter MPC_THR_HOVER Set true to use the value computed by the hover thrust estimator + + UART ESC ID 3 Spin Direction Flag + + - Default + - Reverse + - - Low pass filter cut freq. for numerical velocity derivative - 0.0 - 10 - Hz - 2 + + UART ESC ID 4 Spin Direction Flag + + - Default + - Reverse + - - Maximum horizontal velocity setpoint for manual controlled mode - If velocity setpoint larger than MPC_XY_VEL_MAX is set, then the setpoint will be capped to MPC_XY_VEL_MAX - 3.0 - 20.0 - m/s - 2 + + UART ESC Turtle Mode Cosphi + 0.000 + 1.000 + 10 + 0.001 + + + UART ESC Turtle Mode Crash Flip Motor Deadband + 0 + 100 + 10 1 - - Maximum horizontal velocity in mission - Horizontal velocity used when flying autonomously in e.g. Missions, RTL, Goto. - 3.0 - 20.0 - m/s - 2 + + UART ESC Turtle Mode Crash Flip Motor expo + 0 + 100 + 10 1 - - Maximum horizontal error allowed by the trajectory generator - The integration speed of the trajectory setpoint is linearly reduced with the horizontal position tracking error. When the error is above this parameter, the integration of the trajectory is stopped to wait for the drone. This value can be adjusted depending on the tracking capabilities of the vehicle. - 0.1 - 10.0 - 1 + + UART ESC Turtle Mode Crash Flip Motor STICK_MINF + 0.0 + 100.0 + 10 + 1.0 - - Manual position control stick exponential curve sensitivity - The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve + + UART ESC Turtle Mode Crash Flip Motor Percent + 1 + 100 + 10 + 1 + + + UART ESC verbose logging 0 1 - 2 + true + + - Disabled + - Enabled + - - Proportional gain for horizontal position error - 0.0 - 2.0 - 2 + + + + Enable online mag bias calibration + This enables continuous calibration of the magnetometers before takeoff using gyro data. + true - - Proportional gain for horizontal trajectory position error + + Mag bias estimator learning gain + Increase to make the estimator more responsive Decrease to make the estimator more robust to noise 0.1 - 1.0 - 1 - - - Overall Horizonal Velocity Limit - If set to a value greater than zero, other parameters are automatically set (such as MPC_XY_VEL_MAX or MPC_VEL_MANUAL). If set to a negative value, the existing individual parameters are used. - -20 - 20 + 100 1 - 1 + 0.1 - - Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again - defined as correction acceleration in m/s^2 per m/s^2 velocity derivative - 0.1 - 2.0 - 3 + + + + Enable arm/disarm stick gesture + This determines if moving the left stick to the lower right arms and to the lower left disarms the vehicle. - - Integral gain for horizontal velocity error - defined as correction acceleration in m/s^2 per m velocity integral Non-zero value allows to eliminate steady state errors in the presence of disturbances like wind. - 0.0 - 60.0 - 3 + + + + GPS failure loiter time + The time in seconds the system should do open loop loiter and wait for GPS recovery before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0. + 0 + 3600 + s - - Maximum horizontal velocity - Maximum horizontal velocity in AUTO mode. If higher speeds are commanded in a mission they will be capped to this velocity. + + GPS failure fixed roll angle + Roll in degrees during the loiter after the vehicle has lost GPS in an auto mode (e.g. mission or loiter). 0.0 - 20.0 - m/s - 2 - 1 + 30.0 + deg + 1 + 0.5 - - Proportional gain for horizontal velocity error - defined as correction acceleration in m/s^2 per m/s velocity error - 1.2 - 5.0 - 2 + + Maximal horizontal distance from current position to first waypoint + Failsafe check to prevent running mission stored from previous flight at a new takeoff location. Set a value of zero or less to disable. The mission will not be started if the current waypoint is more distant than MIS_DIST_1WP from the current position. + -1 + 10000 + m + 1 + 100 - - Manual control stick yaw rotation exponential curve - The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve + + Landing abort min altitude + Minimum altitude above landing point that the vehicle will climb to after an aborted landing. Then vehicle will loiter in this altitude until further command is received. Only applies to fixed-wing vehicles. 0 - 1 - 2 + m - - Manual control stick vertical exponential curve - The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve + + Enable yaw control of the mount. (Only affects multicopters and ROI mission items) + If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. If disabled, the vehicle will yaw towards the ROI. 0 1 - 2 + + Disable + Enable + - - Proportional gain for vertical position error - 0.0 - 1.5 - 2 + + Timeout for a successful payload deployment acknowledgement + 0 + s + 1 + 1 - - Overall Vertical Velocity Limit - If set to a value greater than zero, other parameters are automatically set (such as MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED). If set to a negative value, the existing individual parameters are used. - -3 - 8 + + Default take-off altitude + This is the relative altitude the system will take off to if not otherwise specified. + 0 + m 1 0.5 - - Differential gain for vertical velocity error - defined as correction acceleration in m/s^2 per m/s^2 velocity derivative - 0.0 - 2.0 - 3 - - - Integral gain for vertical velocity error - defined as correction acceleration in m/s^2 per m velocity integral Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff. - 0.2 - 3.0 - 3 - - - Maximum vertical descent velocity - Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL). - 0.5 - 4.0 - m/s + + Mission takeoff/landing required + Specifies if a mission has to contain a takeoff and/or mission landing. Validity of configured takeoffs/landings is checked independently of the setting here. + + No requirements + Require a takeoff + Require a landing + Require a takeoff and a landing + Require both a takeoff and a landing, or neither + - - Maximum vertical ascent velocity - Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL). - 0.5 - 8.0 - m/s + + Max yaw error in degrees needed for waypoint heading acceptance + 0 + 90 + deg 1 + 1 - - Proportional gain for vertical velocity error - defined as correction acceleration in m/s^2 per m/s velocity error - 2.0 - 15.0 - 2 - - - Responsiveness - Changes the overall responsiveness of the vehicle. The higher the value, the faster the vehicle will react. If set to a value greater than zero, other parameters are automatically set (such as the acceleration or jerk limits). If set to a negative value, the existing individual parameters are used. + + Time in seconds we wait on reaching target heading at a waypoint if it is forced + If set > 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default. -1 - 1 - 2 - 0.05 - - - Enable weathervane - - - Minimum roll angle setpoint for weathervane controller to demand a yaw-rate - 0 - 5 - deg + 20 + s + 1 + 1 - - Maximum yawrate the weathervane controller is allowed to demand + + Heading behavior in autonomous modes 0 - 120 - deg/s + 4 + + towards waypoint + towards home + away from home + along trajectory + towards waypoint (yaw first) + - - - - Acro mode Expo factor for Roll and Pitch - Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve - 0 - 1 - 2 + + Acceptance Radius + Default acceptance radius, overridden by acceptance radius of waypoint if set. For fixed wing the npfg switch distance is used for horizontal acceptance. + 0.05 + 200.0 + m + 1 + 0.5 - - Acro mode Expo factor for Yaw - Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve - 0 - 1 - 2 + + Force VTOL mode takeoff and land - - Max acro pitch rate - default: 2 turns per second - 0.0 - 1800.0 - deg/s + + FW Altitude Acceptance Radius before a landing + Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller than the standard vertical acceptance because close to the ground higher accuracy is required. + 0.05 + 200.0 + m 1 - 5 - - Max acro roll rate - default: 2 turns per second - 0.0 - 1800.0 - deg/s + + FW Altitude Acceptance Radius + Acceptance radius for fixedwing altitude. + 0.05 + 200.0 + m 1 - 5 - - - Acro mode SuperExpo factor for Roll and Pitch - SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect - 0 - 0.95 - 2 + 0.5 - - Acro mode SuperExpo factor for Yaw - SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect - 0 - 0.95 - 2 + + Loiter radius (FW only) + Default value of loiter radius in FW mode (e.g. for Loiter mode). + 25 + 1000 + m + 1 + 0.5 - - Max acro yaw rate - default 1.5 turns per second - 0.0 - 1800.0 - deg/s + + MC Altitude Acceptance Radius + Acceptance radius for multicopter altitude. + 0.05 + 200.0 + m 1 - 5 + 0.5 - - Battery power level scaler - This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery. + + Minimum Loiter altitude + This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this mode without specifying an altitude (e.g. through Loiter switch on RC). Doesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint ("Go to"). Set to a negative value to disable. + -1 + m + 1 + 0.5 - - Pitch rate D gain - Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - 0.0 - 4 - 0.0005 - - - Pitch rate feedforward - Improves tracking performance. - 0.0 - 4 - - - Pitch rate I gain - Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset. - 0.0 - 3 - 0.01 - - - Pitch rate controller gain - Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_PITCHRATE_K * (MC_PITCHRATE_P * error + MC_PITCHRATE_I * error_integral + MC_PITCHRATE_D * error_derivative) Set MC_PITCHRATE_P=1 to implement a PID in the ideal form. Set MC_PITCHRATE_K=1 to implement a PID in the parallel form. - 0.01 - 5.0 - 4 - 0.0005 - - - Pitch rate P gain - Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s. - 0.01 - 0.6 - 3 - 0.01 - - - Pitch rate integrator limit - Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes. - 0.0 - 2 - 0.01 - - - Roll rate D gain - Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - 0.0 - 0.01 - 4 - 0.0005 - - - Roll rate feedforward - Improves tracking performance. - 0.0 - 4 - - - Roll rate I gain - Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset. - 0.0 - 3 - 0.01 - - - Roll rate controller gain - Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_ROLLRATE_K * (MC_ROLLRATE_P * error + MC_ROLLRATE_I * error_integral + MC_ROLLRATE_D * error_derivative) Set MC_ROLLRATE_P=1 to implement a PID in the ideal form. Set MC_ROLLRATE_K=1 to implement a PID in the parallel form. - 0.01 - 5.0 - 4 - 0.0005 - - - Roll rate P gain - Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s. - 0.01 - 0.5 - 3 - 0.01 - - - Roll rate integrator limit - Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes. - 0.0 - 2 - 0.01 - - - Yaw rate D gain - Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. - 0.0 - 2 - 0.01 + + Set traffic avoidance mode + Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders + + Disabled + Warn only + Return mode + Land mode + Position Hold mode + - - Yaw rate feedforward - Improves tracking performance. - 0.0 - 4 - 0.01 + + Set NAV TRAFFIC AVOID horizontal distance + Defines a crosstrack horizontal distance + 500 + m - - Yaw rate I gain - Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset. - 0.0 - 2 - 0.01 + + Set NAV TRAFFIC AVOID vertical distance + 10 + 500 + m - - Yaw rate controller gain - Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_YAWRATE_K * (MC_YAWRATE_P * error + MC_YAWRATE_I * error_integral + MC_YAWRATE_D * error_derivative) Set MC_YAWRATE_P=1 to implement a PID in the ideal form. Set MC_YAWRATE_K=1 to implement a PID in the parallel form. - 0.0 - 5.0 - 4 - 0.0005 + + Estimated time until collision + Minimum acceptable time until collsion. Assumes constant speed over 3d distance. + 1 + 900000000 + s - - Yaw rate P gain - Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s. - 0.0 - 0.6 - 2 - 0.01 + + Vehicle base weight + This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight. + kg + 1 + 0.5 - - Yaw rate integrator limit - Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes. - 0.0 - 2 - 0.01 + + Vehicle gross weight + This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added or removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight. + kg + 1 + 0.1 - - - Enable/Disable the ATXXX OSD Chip - Configure the ATXXXX OSD Chip (mounted on the OmnibusF4SD board) and select the transmission standard. - true + + + 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 (i.e. the vehicle is not tuned yet). Enabling air-mode for yaw requires the use of an arming switch. Disabled - NTSC - PAL + Roll/Pitch + Roll/Pitch/Yaw - - - Minimum motor rise time (slew rate limit) - Minimum time allowed for the motor input signal to pass through a range of 1000 PWM units. A value x means that the motor signal can only go from 1000 to 2000 PWM in maximum x seconds. Zero means that slew rate limiting is disabled. - 0.0 - s/(1000*PWM) + + + Stabilize the mount + Set to true for servo gimbal, false for passthrough. This is required for a gimbal which is not capable of stabilizing itself and relies on the IMU's attitude estimation. + 0 + 2 + + Disable + Stabilize all axis + Stabilize yaw for absolute/lock mode. + - - PWM aux 1 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used - -1 - 2150 - us + + Pitch maximum when landed + -90.0 + 90.0 + deg + 1 - - PWM aux 2 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used - -1 - 2150 - us + + Pitch minimum when landed + -90.0 + 90.0 + deg + 1 - - PWM aux 3 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used - -1 - 2150 - us + + Auxiliary channel to control pitch (in AUX input or manual mode) + 0 + 6 + + Disable + AUX1 + AUX2 + AUX3 + AUX4 + AUX5 + AUX6 + - - PWM aux 4 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used - -1 - 2150 - us + + Auxiliary channel to control roll (in AUX input or manual mode) + 0 + 6 + + Disable + AUX1 + AUX2 + AUX3 + AUX4 + AUX5 + AUX6 + - - PWM aux 5 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used - -1 - 2150 - us + + Auxiliary channel to control yaw (in AUX input or manual mode) + 0 + 6 + + Disable + AUX1 + AUX2 + AUX3 + AUX4 + AUX5 + AUX6 + - - PWM aux 6 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used - -1 - 2150 - us + + Mavlink Component ID of the mount + If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID. - - PWM aux 7 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used - -1 - 2150 - us + + Mavlink System ID of the mount + If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID. - - PWM aux 8 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARM will be used + + Mount input mode + This is the protocol used between the ground station and the autopilot. Recommended is Auto, RC only or MAVLink gimbal protocol v2. The rest will be deprecated. -1 - 2150 - us + 4 + true + + DISABLED + Auto (RC and MAVLink gimbal protocol v2) + RC + MAVLINK_ROI (protocol v1, to be deprecated) + MAVLINK_DO_MOUNT (protocol v1, to be deprecated) + MAVlink gimbal protocol v2 + - - PWM aux disarmed value - This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. + + Mount output mode + This is the protocol used between the autopilot and a connected gimbal. Recommended is the MAVLink gimbal protocol v2 if the gimbal supports it. 0 - 2200 - us - - - PWM aux 1 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us - - - PWM aux 2 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us - - - PWM aux 3 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us - - - PWM aux 4 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us - - - PWM aux 5 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us - - - PWM aux 6 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us - - - PWM aux 7 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us - - - PWM aux 8 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us - - - PWM aux maximum value - Set to 2000 for industry default or 2100 to increase servo travel. - 1600 - 2200 - us - - - PWM aux 1 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used - -1 - 2150 - us - - - PWM aux 2 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used - -1 - 2150 - us - - - PWM aux 3 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used - -1 - 2150 - us - - - PWM aux 4 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used - -1 - 2150 - us - - - PWM aux 5 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used - -1 - 2150 - us - - - PWM aux 6 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used - -1 - 2150 - us - - - PWM aux 7 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used - -1 - 2150 - us - - - PWM aux 8 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MAX will be used - -1 - 2150 - us - - - PWM aux minimum value - Set to 1000 for industry default or 900 to increase servo travel. - 800 - 1400 - us + 2 + true + + AUX + MAVLink gimbal protocol v1 + MAVLink gimbal protocol v2 + - - PWM aux 1 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used - -1 - 1600 - us + + Offset for pitch channel output in degrees + -360.0 + 360.0 + deg + 1 - - PWM aux 2 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used - -1 - 1600 - us + + Offset for roll channel output in degrees + -360.0 + 360.0 + deg + 1 - - PWM aux 3 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used - -1 - 1600 - us + + Offset for yaw channel output in degrees + -360.0 + 360.0 + deg + 1 - - PWM aux 4 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used - -1 - 1600 - us + + Range of pitch channel output in degrees (only in AUX output mode) + 1.0 + 720.0 + deg + 1 - - PWM aux 5 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used - -1 - 1600 - us + + Range of roll channel output in degrees (only in AUX output mode) + 1.0 + 720.0 + deg + 1 - - PWM aux 6 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used - -1 - 1600 - us + + Range of yaw channel output in degrees (only in AUX output mode) + 1.0 + 720.0 + deg + 1 - - PWM aux 7 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used - -1 - 1600 - us + + Angular pitch rate for manual input in degrees/second + Full stick input [-1..1] translats to [-pitch rate..pitch rate]. + 1.0 + 90.0 + deg/s - - PWM aux 8 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_AUX_MIN will be used - -1 - 1600 - us + + Angular yaw rate for manual input in degrees/second + Full stick input [-1..1] translats to [-yaw rate..yaw rate]. + 1.0 + 90.0 + deg/s - - PWM channels used as ESC outputs - Number representing the channels e.g. 134 - Channel 1, 3 and 4. Global e.g. PWM_AUX_MIN/MAX/DISARM limits only apply to these channels. + + Input mode for RC gimbal input 0 - 123456789 - - - PWM aux output frequency - Set to 400 for industry default or 1000 for high frequency ESCs. Set to 0 for Oneshot125. - -1 - 2000 - Hz + 1 + + Angle + Angular rate + - - PWM aux 1 rate - Set the default PWM output frequency for the aux outputs + + + + Acro mode roll, pitch expo factor + Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve 0 - 400 - Hz - - - PWM aux 1 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + 1 + 2 - - PWM aux 2 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + Acro mode yaw expo factor + Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve + 0 + 1 + 2 - - PWM aux 3 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + Acro mode maximum pitch rate + Full stick deflection leads to this rate. + 0.0 + 1800.0 + deg/s + 1 + 5 - - PWM aux 4 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + Acro mode maximum roll rate + Full stick deflection leads to this rate. + 0.0 + 1800.0 + deg/s + 1 + 5 - - PWM aux 5 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + Acro mode roll, pitch super expo factor + "Superexponential" factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect + 0 + 0.95 + 2 - - PWM aux 6 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + Acro mode yaw super expo factor + "Superexponential" factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect + 0 + 0.95 + 2 - - PWM aux 7 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + Acro mode maximum yaw rate + Full stick deflection leads to this rate. + 0.0 + 1800.0 + deg/s + 1 + 5 - - PWM aux 8 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + + + Max pitch rate + Limit for pitch rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro. + 0.0 + 1800.0 + deg/s + 1 + 5 - - PWM aux 1 trim value - Set to normalized offset - -0.2 - 0.2 + + Pitch P gain + Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad. + 0.0 + 12 2 + 0.1 - - PWM aux 2 trim value - Set to normalized offset - -0.2 - 0.2 - 2 + + Max roll rate + Limit for roll rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro. + 0.0 + 1800.0 + deg/s + 1 + 5 - - PWM aux 3 trim value - Set to normalized offset - -0.2 - 0.2 + + Roll P gain + Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. + 0.0 + 12 2 + 0.1 - - PWM aux 4 trim value - Set to normalized offset - -0.2 - 0.2 - 2 + + Max yaw rate + 0.0 + 1800.0 + deg/s + 1 + 5 - - PWM aux 5 trim value - Set to normalized offset - -0.2 - 0.2 + + Yaw P gain + Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad. + 0.0 + 5 2 + 0.1 - - PWM aux 6 trim value - Set to normalized offset - -0.2 - 0.2 + + Yaw weight + A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. Deprioritizing yaw is necessary because multicopters have much less control authority in yaw compared to the other axes and it makes sense because yaw is not critical for stable hovering or 3D navigation. For yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain. + 0.0 + 1.0 2 + 0.1 - - PWM aux 7 trim value - Set to normalized offset - -0.2 - 0.2 - 2 + + Max yaw rate in autonomous modes + Limits the rate of change of the yaw setpoint to avoid large control output and mixer saturation. + 0 + 360 + deg/s + 0 + 5 - - PWM aux 8 trim value - Set to normalized offset - -0.2 - 0.2 - 2 + + + + Average delay of the range sensor message plus the tracking delay of the position controller in seconds + Only used in Position mode. + 0 + 1 + s - - PWM extra 1 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used + + Minimum distance the vehicle should keep to all obstacles + Only used in Position mode. Collision avoidance is disabled by setting this parameter to a negative value -1 - 2150 - us + 15 + m - - PWM extra 2 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used - -1 - 2150 - us + + Boolean to allow moving into directions where there is no sensor data (outside FOV) + Only used in Position mode. - - PWM extra 3 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used - -1 - 2150 - us + + Angle left/right from the commanded setpoint by which the collision prevention algorithm can choose to change the setpoint direction + Only used in Position mode. + 0 + 90 + deg - - PWM extra 4 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used - -1 - 2150 - us + + Manual tilt input filter time constant + Setting this parameter to 0 disables the filter + 0.0 + 2.0 + s + 2 - - PWM extra 5 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used - -1 - 2150 - us + + Maximum downwards acceleration in climb rate controlled modes + 2 + 15 + m/s^2 + 1 + 1 - - PWM extra 6 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used - -1 - 2150 - us + + Acceleration for autonomous and for manual modes + When piloting manually, this parameter is only used in MPC_POS_MODE 4. + 2 + 15 + m/s^2 + 1 + 1 - - PWM extra 7 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used - -1 - 2150 - us + + Maximum horizontal acceleration + MPC_POS_MODE 1 just deceleration 3 acceleration and deceleration 4 not used, use MPC_ACC_HOR instead + 2 + 15 + m/s^2 + 2 + 1 - - PWM extra 8 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_EXTRA_DISARM will be used - -1 - 2150 - us + + Maximum upwards acceleration in climb rate controlled modes + 2 + 15 + m/s^2 + 1 + 1 - - PWM extra disarmed value - This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. + + Altitude reference mode + Set to 0 to control height relative to the earth frame origin. This origin may move up and down in flight due to sensor drift. Set to 1 to control height relative to estimated distance to ground. The vehicle will move up and down with terrain height variation. Requires a distance to ground sensor. The height controller will revert to using height above origin if the distance to ground estimate becomes invalid as indicated by the local_position.distance_bottom_valid message being false. Set to 2 to control height relative to ground (requires a distance sensor) when stationary and relative to earth frame origin when moving horizontally. The speed threshold is controlled by the MPC_HOLD_MAX_XY parameter. 0 - 2200 - us + 2 + + Altitude following + Terrain following + Terrain hold + - - PWM extra 1 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + + Deadzone for sticks in manual piloted modes + Does not apply to manual throttle and direct attitude piloting by stick. 0 - 2150 - us + 1 + 2 + 0.01 - - PWM extra 2 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + + Maximum horizontal velocity for which position hold is enabled (use 0 to disable check) + Only used with MPC_POS_MODE 0 or MPC_ALT_MODE 2 0 - 2150 - us + 3 + m/s + 2 - - PWM extra 3 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + + Maximum vertical velocity for which position hold is enabled (use 0 to disable check) + Only used with MPC_ALT_MODE 1 0 - 2150 - us + 3 + m/s + 2 - - PWM extra 4 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - 0 - 2150 - us + + Jerk limit in autonomous modes + Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions but also limited agility. + 1 + 80 + m/s^3 + 1 + 1 - - PWM extra 5 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - 0 - 2150 - us + + Maximum horizontal and vertical jerk in Position/Altitude mode + Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother motions but limits agility (how fast it can change directions or break). Setting this to the maximum value essentially disables the limit. Only used with smooth MPC_POS_MODE 3 and 4. + 0.5 + 500 + m/s^3 + 0 + 1 - - PWM extra 6 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + + Altitude for 1. step of slow landing (descend) + Below this altitude descending velocity gets limited to a value between "MPC_Z_VEL_MAX_DN" (or "MPC_Z_V_AUTO_DN") and "MPC_LAND_SPEED" Value needs to be higher than "MPC_LAND_ALT2" 0 - 2150 - us + 122 + m + 1 - - PWM extra 7 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + + Altitude for 2. step of slow landing (landing) + Below this altitude descending velocity gets limited to "MPC_LAND_SPEED" Value needs to be lower than "MPC_LAND_ALT1" 0 - 2150 - us + 122 + m + 1 - - PWM extra 8 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) + + Altitude for 3. step of slow landing + Below this altitude descending velocity gets limited to "MPC_LAND_CRWL", if LIDAR available. No effect if LIDAR not available 0 - 2150 - us + 122 + m + 1 - - PWM extra maximum value - Set to 2000 for industry default or 2100 to increase servo travel. - 1600 - 2200 - us + + Land crawl descend rate + Used below MPC_LAND_ALT3 if distance sensor data is availabe. + 0.1 + m/s + 1 - - PWM extra 1 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used - -1 - 2150 - us + + User assisted landing radius + When nudging is enabled (see MPC_LAND_RC_HELP), this controls the maximum allowed horizontal displacement from the original landing point. + 0 + m + 0 + 1 - - PWM extra 2 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used - -1 - 2150 - us + + Enable nudging based on user input during autonomous land routine + Using stick input the vehicle can be moved horizontally and yawed. The descend speed is amended: stick full up - 0 stick centered - MPC_LAND_SPEED stick full down - 2 * MPC_LAND_SPEED Manual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE). + 0 + 1 + + Nudging disabled + Nudging enabled + - - PWM extra 3 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used - -1 - 2150 - us + + Landing descend rate + 0.6 + m/s + 1 - - PWM extra 4 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used - -1 - 2150 - us + + Minimum collective thrust in Stabilized mode + The value is mapped to the lowest throttle stick position in Stabilized mode. Too low collective thrust leads to loss of roll/pitch/yaw torque control authority. Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE). + 0 + 1 + norm + 2 + 0.01 - - PWM extra 5 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used - -1 - 2150 - us + + Maximal tilt angle in Stabilized or Altitude mode + 0 + 90 + deg + 0 + 1 - - PWM extra 6 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used - -1 - 2150 - us + + Max manual yaw rate for Stabilized, Altitude, Position mode + 0 + 400 + deg/s + 0 + 10 - - PWM extra 7 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used - -1 - 2150 - us + + Manual yaw rate input filter time constant + Not used in Stabilized mode Setting this parameter to 0 disables the filter + 0 + 5 + s + 2 + 0.01 - - PWM extra 8 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MAX will be used - -1 - 2150 - us + + Position/Altitude mode variant + The supported sub-modes are: 0 Sticks directly map to velocity setpoints without smoothing. Also applies to vertical direction and Altitude mode. Useful for velocity control tuning. 3 Sticks map to velocity but with maximum acceleration and jerk limits based on jerk optimized trajectory generator (different algorithm than 1). 4 Sticks map to acceleration and there's a virtual brake drag + + Direct velocity + Smoothed velocity + Acceleration based + - - PWM extra minimum value - Set to 1000 for industry default or 900 to increase servo travel. - 800 - 1400 - us + + Thrust curve mapping in Stabilized Mode + This parameter defines how the throttle stick input is mapped to collective thrust in Stabilized mode. In case the default is used ('Rescale to hover thrust'), the stick input is linearly rescaled, such that a centered stick corresponds to the hover throttle (see MPC_THR_HOVER). Select 'No Rescale' to directly map the stick 1:1 to the output. This can be useful in case the hover thrust is very low and the default would lead to too much distortion (e.g. if hover thrust is set to 20%, then 80% of the upper thrust range is squeezed into the upper half of the stick range). Note: In case MPC_THR_HOVER is set to 50%, the modes 0 and 1 are the same. + + Rescale to hover thrust + No Rescale + - - PWM extra 1 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used - -1 - 1600 - us + + Vertical thrust required to hover + Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE). Used for initialization of the hover thrust estimator (see MPC_USE_HTE). The estimated hover thrust is used as base for zero vertical acceleration in altitude control. The hover thrust is important for land detection to work correctly. + 0.1 + 0.8 + norm + 2 + 0.01 - - PWM extra 2 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used - -1 - 1600 - us + + Maximum collective thrust in climb rate controlled modes + Limit allowed thrust e.g. for indoor test of overpowered vehicle. + 0 + 1 + norm + 2 + 0.05 - - PWM extra 3 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used - -1 - 1600 - us + + Minimum collective thrust in climb rate controlled modes + Too low thrust leads to loss of roll/pitch/yaw torque control authority. With airmode enabled this parameters can be set to 0 while still keeping torque authority (see MC_AIRMODE). + 0.05 + 0.5 + norm + 2 + 0.01 - - PWM extra 4 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used - -1 - 1600 - us + + Horizontal thrust margin + Margin that is kept for horizontal control when higher priority vertical thrust is saturated. To avoid completely starving horizontal control with high vertical error. + 0 + 0.5 + norm + 2 + 0.01 - - PWM extra 5 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used - -1 - 1600 - us + + Maximum tilt angle in air + Absolute maximum for all velocity or acceleration controlled modes. Any higher value is truncated. + 20 + 89 + deg + 0 + 1 - - PWM extra 6 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used - -1 - 1600 - us + + Maximum tilt during inital takeoff ramp + Tighter tilt limit during takeoff to avoid tip over. + 5 + 89 + deg + 0 + 1 - - PWM extra 7 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used - -1 - 1600 - us + + Smooth takeoff ramp time constant + Increasing this value will make climb rate controlled takeoff slower. If it's too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp + 0 + 5 + s - - PWM extra 8 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_EXTRA_MIN will be used - -1 - 1600 - us + + Takeoff climb rate + 1 + 5 + m/s + 2 - - PWM extra output frequency - Set to 400 for industry default or 1000 for high frequency ESCs. Set to 0 for Oneshot125. - -1 - 2000 - Hz + + Hover thrust estimator + Disable to use the fixed parameter MPC_THR_HOVER Enable to use the hover thrust estimator - - PWM extra 1 rate - Set the default PWM output frequency for the main outputs + + Numerical velocity derivative low pass cutoff frequency 0 - 400 + 10 Hz + 1 + 0.5 - - PWM extra 1 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM extra 2 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + Maximum horizontal velocity setpoint in Position mode + Must be smaller than MPC_XY_VEL_MAX. The maximum sideways and backward speed can be set differently using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively. + 3 + 20 + m/s + 1 + 1 - - PWM extra 3 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + Maximum backward velocity in Position mode + If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. + -1 + 20 + m/s + 1 + 1 - - PWM extra 4 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + Maximum sideways velocity in Position mode + If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. + -1 + 20 + m/s + 1 + 1 - - PWM extra 5 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + Default horizontal velocity in autonomous modes + e.g. in Missions, RTL, Goto if the waypoint does not specify differently + 3 + 20 + m/s + 0 + 1 - - PWM extra 6 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + Maximum horizontal error allowed by the trajectory generator + The integration speed of the trajectory setpoint is linearly reduced with the horizontal position tracking error. When the error is above this parameter, the integration of the trajectory is stopped to wait for the drone. This value can be adjusted depending on the tracking capabilities of the vehicle. + 0.1 + 10 + 1 + 1 - - PWM extra 7 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. + + Manual position control stick exponential curve sensitivity + The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve + 0 + 1 + 2 + 0.01 - - PWM extra 8 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM extra 1 trim value - Set to normalized offset - -0.2 - 0.2 + + Proportional gain for horizontal position error + Defined as corrective velocity in m/s per m position error + 0 + 2 2 + 0.1 - - PWM extra 2 trim value - Set to normalized offset - -0.2 - 0.2 - 2 + + Proportional gain for horizontal trajectory position error + 0.1 + 1 + 1 + 0.1 - - PWM extra 3 trim value - Set to normalized offset - -0.2 - 0.2 - 2 + + Overall Horizontal Velocity Limit + If set to a value greater than zero, other parameters are automatically set (such as MPC_XY_VEL_MAX or MPC_VEL_MANUAL). If set to a negative value, the existing individual parameters are used. + -20 + 20 + 1 + 1 - - PWM extra 4 trim value - Set to normalized offset - -0.2 - 0.2 + + Differential gain for horizontal velocity error + Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative + 0.1 + 2 2 + 0.02 - - PWM extra 5 trim value - Set to normalized offset - -0.2 - 0.2 + + Integral gain for horizontal velocity error + Defined as correction acceleration in m/s^2 per m velocity integral Allows to eliminate steady state errors in disturbances like wind. + 0 + 60 2 + 0.02 - - PWM extra 6 trim value - Set to normalized offset - -0.2 - 0.2 - 2 + + Maximum horizontal velocity + Absolute maximum for all velocity controlled modes. Any higher value is truncated. + 0 + 20 + m/s + 1 + 1 - - PWM extra 7 trim value - Set to normalized offset - -0.2 - 0.2 + + Proportional gain for horizontal velocity error + Defined as corrective acceleration in m/s^2 per m/s velocity error + 1.2 + 5 2 + 0.1 - - PWM extra 8 trim value - Set to normalized offset - -0.2 - 0.2 + + Manual control stick yaw rotation exponential curve + The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve + 0 + 1 2 + 0.01 - - PWM main 1 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us - - - PWM main 10 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us + + Manual control stick vertical exponential curve + The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve + 0 + 1 + 2 + 0.01 - - PWM main 11 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us + + Proportional gain for vertical position error + Defined as corrective velocity in m/s per m position error + 0.1 + 1.5 + 2 + 0.1 - - PWM main 12 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us + + Overall Vertical Velocity Limit + If set to a value greater than zero, other parameters are automatically set (such as MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED). If set to a negative value, the existing individual parameters are used. + -3 + 8 + 1 + 0.5 - - PWM main 13 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us + + Differential gain for vertical velocity error + Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative + 0 + 2 + 2 + 0.02 - - PWM main 14 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us + + Integral gain for vertical velocity error + Defined as corrective acceleration in m/s^2 per m velocity integral + 0.2 + 3 + 2 + 0.1 - - PWM main 2 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us + + Maximum descent velocity + Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP + 0.5 + 4 + m/s + 1 + 0.1 - - PWM main 3 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us + + Maximum ascent velocity + Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP + 0.5 + 8 + m/s + 1 + 0.1 - - PWM main 4 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us + + Proportional gain for vertical velocity error + Defined as corrective acceleration in m/s^2 per m/s velocity error + 2 + 15 + 2 + 0.1 - - PWM main 5 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us + + Descent velocity in autonomous modes + For manual modes and offboard, see MPC_Z_VEL_MAX_DN + 0.5 + 4 + m/s + 1 + 0.5 - - PWM main 6 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us + + Ascent velocity in autonomous modes + For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP + 0.5 + 8 + m/s + 1 + 0.5 - - PWM main 7 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used + + Responsiveness + Changes the overall responsiveness of the vehicle. The higher the value, the faster the vehicle will react. If set to a value greater than zero, other parameters are automatically set (such as the acceleration or jerk limits). If set to a negative value, the existing individual parameters are used. -1 - 2150 - us + 1 + 2 + 0.05 - - PWM main 8 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us + + Enable weathervane - - PWM main 9 disarmed value - This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_MAIN_DISARM will be used - -1 - 2150 - us + + Minimum roll angle setpoint for weathervane controller to demand a yaw-rate + 0 + 5 + deg - - PWM main disarmed value - This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. + + Maximum yawrate the weathervane controller is allowed to demand 0 - 2200 - us + 120 + deg/s - - PWM main 1 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + + + Battery power level scaler + This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery. - - PWM main 10 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + Pitch rate D gain + Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + 0.0 + 4 + 0.0005 - - PWM main 11 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + Pitch rate feedforward + Improves tracking performance. + 0.0 + 4 - - PWM main 12 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + Pitch rate I gain + Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset. + 0.0 + 3 + 0.01 - - PWM main 13 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + Pitch rate controller gain + Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_PITCHRATE_K * (MC_PITCHRATE_P * error + MC_PITCHRATE_I * error_integral + MC_PITCHRATE_D * error_derivative) Set MC_PITCHRATE_P=1 to implement a PID in the ideal form. Set MC_PITCHRATE_K=1 to implement a PID in the parallel form. + 0.01 + 5.0 + 4 + 0.0005 - - PWM main 14 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + Pitch rate P gain + Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s. + 0.01 + 0.6 + 3 + 0.01 - - PWM main 2 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + Pitch rate integrator limit + Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes. + 0.0 + 2 + 0.01 - - PWM main 3 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + Roll rate D gain + Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + 0.0 + 0.01 + 4 + 0.0005 - - PWM main 4 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + Roll rate feedforward + Improves tracking performance. + 0.0 + 4 - - PWM main 5 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + Roll rate I gain + Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset. + 0.0 + 3 + 0.01 - - PWM main 6 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + Roll rate controller gain + Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_ROLLRATE_K * (MC_ROLLRATE_P * error + MC_ROLLRATE_I * error_integral + MC_ROLLRATE_D * error_derivative) Set MC_ROLLRATE_P=1 to implement a PID in the ideal form. Set MC_ROLLRATE_K=1 to implement a PID in the parallel form. + 0.01 + 5.0 + 4 + 0.0005 - - PWM main 7 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + Roll rate P gain + Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s. + 0.01 + 0.5 + 3 + 0.01 - - PWM main 8 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us + + Roll rate integrator limit + Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes. + 0.0 + 2 + 0.01 - - PWM main 9 failsafe value - This is the PWM pulse the autopilot is outputting if in failsafe mode. When set to -1 the value is set automatically depending if the actuator is a motor (900us) or a servo (1500us) - -1 - 2150 - us - - - PWM main maximum value - Set to 2000 for industry default or 2100 to increase servo travel. - 1600 - 2200 - us - - - PWM main 1 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 10 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 11 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 12 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 13 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 14 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 2 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 3 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 4 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 5 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 6 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 7 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 8 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main 9 maximum value - This is the maximum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MAX will be used - -1 - 2150 - us - - - PWM main minimum value - Set to 1000 for industry default or 900 to increase servo travel. - 800 - 1400 - us - - - PWM main 1 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 10 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 11 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 12 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 13 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 14 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 2 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 3 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 4 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 5 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 6 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 7 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 8 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM main 9 minimum value - This is the minimum PWM pulse the autopilot is allowed to output. When set to -1 the value for PWM_MAIN_MIN will be used - -1 - 1600 - us - - - PWM channels used as ESC outputs - Number representing the channels e.g. 134 - Channel 1, 3 and 4. Global e.g. PWM_MAIN_MIN/MAX/DISARM limits only apply to these channels. - 0 - 123456789 - - - PWM main output frequency - Set to 400 for industry default or 1000 for high frequency ESCs. Set to 0 for Oneshot125. - -1 - 2000 - Hz - - - PWM main 1 rate - Set the default PWM output frequency for the main outputs - 0 - 400 - Hz - - - PWM main 1 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 10 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 11 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 12 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 13 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 14 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 2 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 3 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 4 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 5 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 6 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 7 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 8 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 9 reverse value - Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction. - - - PWM main 1 trim value - Set to normalized offset - -0.2 - 0.2 - 2 - - - PWM main 10 trim value - Set to normalized offset - -0.2 - 0.2 - 2 - - - PWM main 11 trim value - Set to normalized offset - -0.2 - 0.2 - 2 - - - PWM main 12 trim value - Set to normalized offset - -0.2 - 0.2 - 2 - - - PWM main 13 trim value - Set to normalized offset - -0.2 - 0.2 - 2 - - - PWM main 14 trim value - Set to normalized offset - -0.2 - 0.2 - 2 - - - PWM main 2 trim value - Set to normalized offset - -0.2 - 0.2 + + Yaw rate D gain + Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + 0.0 2 + 0.01 - - PWM main 3 trim value - Set to normalized offset - -0.2 - 0.2 - 2 + + Yaw rate feedforward + Improves tracking performance. + 0.0 + 4 + 0.01 - - PWM main 4 trim value - Set to normalized offset - -0.2 - 0.2 + + Yaw rate I gain + Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset. + 0.0 2 + 0.01 - - PWM main 5 trim value - Set to normalized offset - -0.2 - 0.2 - 2 + + Yaw rate controller gain + Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_YAWRATE_K * (MC_YAWRATE_P * error + MC_YAWRATE_I * error_integral + MC_YAWRATE_D * error_derivative) Set MC_YAWRATE_P=1 to implement a PID in the ideal form. Set MC_YAWRATE_K=1 to implement a PID in the parallel form. + 0.0 + 5.0 + 4 + 0.0005 - - PWM main 6 trim value - Set to normalized offset - -0.2 - 0.2 + + Yaw rate P gain + Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s. + 0.0 + 0.6 2 + 0.01 - - PWM main 7 trim value - Set to normalized offset - -0.2 - 0.2 + + Yaw rate integrator limit + Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes. + 0.0 2 + 0.01 - - PWM main 8 trim value - Set to normalized offset - -0.2 - 0.2 - 2 + + + + Enable/Disable the ATXXX OSD Chip + Configure the ATXXXX OSD Chip (mounted on the OmnibusF4SD board) and select the transmission standard. + true + + Disabled + NTSC + PAL + - - PWM main 9 trim value - Set to normalized offset - -0.2 - 0.2 - 2 + + + + Minimum motor rise time (slew rate limit) + Minimum time allowed for the motor input signal to pass through a range of 1000 PWM units. A value x means that the motor signal can only go from 1000 to 2000 PWM in minimum x seconds. Zero means that slew rate limiting is disabled. + 0.0 + s/(1000*PWM) S.BUS out @@ -7140,6 +5834,8 @@ Parameter used to model the nonlinear relationship between motor control signal (e.g. PWM) and static thrust. The model is: rel_thrust = factor * rel_signal^2 + (1-factor) * rel_signal, where rel_thrust is the normalized thrust between 0 and 1, and rel_signal is the relative motor control signal between 0 and 1. 0.0 1.0 + 1 + 0.1 @@ -7195,44 +5891,6 @@ 0.1 - - - Serial Configuration for FastRTPS - Configure on which serial port to run FastRTPS. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - - - Serial Configuration for MAVLink + FastRTPS - Configure on which serial port to run MAVLink + FastRTPS. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - - RC channel 10 dead zone @@ -7266,7 +5924,7 @@ RC channel 10 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7303,7 +5961,7 @@ RC channel 11 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7340,7 +5998,7 @@ RC channel 12 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7377,7 +6035,7 @@ RC channel 13 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7414,7 +6072,7 @@ RC channel 14 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7451,7 +6109,7 @@ RC channel 15 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7488,7 +6146,7 @@ RC channel 16 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7525,7 +6183,7 @@ RC channel 17 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7562,7 +6220,7 @@ RC channel 18 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7600,7 +6258,7 @@ RC channel 1 trim - Mid point value (same as min for throttle) + Mid point value 800.0 2200.0 us @@ -7638,7 +6296,7 @@ RC channel 2 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7676,7 +6334,7 @@ RC channel 3 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7714,7 +6372,7 @@ RC channel 4 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7751,7 +6409,7 @@ RC channel 5 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7788,7 +6446,7 @@ RC channel 6 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7825,7 +6483,7 @@ RC channel 7 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7862,7 +6520,7 @@ RC channel 8 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7899,7 +6557,7 @@ RC channel 9 trim - Mid point value (has to be set to the same as min for throttle channel). + Mid point value 800.0 2200.0 us @@ -7912,7 +6570,7 @@ Failsafe channel PWM threshold - Set to a value slightly above the PWM value assumed by throttle in a failsafe event, but ensure it is below the PWM value assumed by throttle during normal operation. Use RC_MAP_FAILSAFE to specify which channel is used to check. Note: The default value of 0 is below the epxed range and hence disables the feature. + Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold. By default this is the throttle channel. Set to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event, but below the minimum PWM value for the channel during normal operation. Note: The default value of 0 disables the feature (it is below the expected range). 0 2200 us @@ -8076,9 +6734,35 @@ Channel 18 + + RC channel to engage the main motor (for helicopters) + 0 + 18 + + Unassigned + Channel 1 + Channel 2 + Channel 3 + Channel 4 + Channel 5 + Channel 6 + Channel 7 + Channel 8 + Channel 9 + Channel 10 + Channel 11 + Channel 12 + Channel 13 + Channel 14 + Channel 15 + Channel 16 + Channel 17 + Channel 18 + + Failsafe channel mapping - Configures which channel is used by the receiver to indicate the signal was lost. Futaba receivers do report that way. If 0, whichever channel is mapped to throttle is used otherwise the value indicates the specific RC channel to use Use RC_FAILS_THR to set the threshold indicating lost signal. By default it's below the expected range and hence diabled. + Configures which RC channel is used by the receiver to indicate the signal was lost (on receivers that use output a fixed signal value to report lost signal). If set to 0, the channel mapped to throttle is used. Use RC_FAILS_THR to set the threshold indicating lost signal. By default it's below the expected range and hence disabled. 0 18 @@ -8333,50 +7017,38 @@ Pitch trim - The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. - -0.25 - 0.25 + The trim value is the actuator control value the system needs for straight and level flight. + -0.5 + 0.5 2 0.01 Roll trim - The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. - -0.25 - 0.25 + The trim value is the actuator control value the system needs for straight and level flight. + -0.5 + 0.5 2 0.01 Yaw trim - The trim value is the actuator control value the system needs for straight and level flight. It can be calibrated by flying manually straight and level using the RC trims and copying them using the GCS. - -0.25 - 0.25 + The trim value is the actuator control value the system needs for straight and level flight. + -0.5 + 0.5 2 0.01 - - Threshold for selecting acro mode - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th - -1 - 1 - Threshold for the arm switch 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th -1 1 - - Threshold for selecting assist mode - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th - -1 - 1 - - - Threshold for selecting auto mode + + Threshold for selecting main motor engage 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th -1 1 @@ -8399,14 +7071,8 @@ -1 1 - - Threshold for the manual switch - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th - -1 - 1 - - Acro switch channel + Acro switch channel (deprecated) 0 18 @@ -8511,8 +7177,34 @@ Channel 18 - - Landing gear switch channel + + Button flight mode selection + This bitmask allows to specify multiple channels for changing flight modes using momentary buttons. Each channel is assigned to a mode slot ((lowest channel = slot 1). The resulting modes for each slot X is defined by the COM_FLTMODEX parameters. The functionality can be used only if RC_MAP_FLTMODE is disabled. The maximum number of available slots and hence bits set in the mask is 6. + 0 + 258048 + + Mask Channel 1 as a mode button + Mask Channel 2 as a mode button + Mask Channel 3 as a mode button + Mask Channel 4 as a mode button + Mask Channel 5 as a mode button + Mask Channel 6 as a mode button + Mask Channel 7 as a mode button + Mask Channel 8 as a mode button + Mask Channel 9 as a mode button + Mask Channel 10 as a mode button + Mask Channel 11 as a mode button + Mask Channel 12 as a mode button + Mask Channel 13 as a mode button + Mask Channel 14 as a mode button + Mask Channel 15 as a mode button + Mask Channel 16 as a mode button + Mask Channel 17 as a mode button + Mask Channel 18 as a mode button + + + + Landing gear switch channel 0 18 @@ -8590,7 +7282,7 @@ - Manual switch channel mapping + Manual switch channel mapping (deprecated) 0 18 @@ -8616,7 +7308,7 @@ - Mode switch channel mapping + Mode switch channel mapping (deprecated) This is the main flight mode selector. The channel index (starting from 1 for channel 1) indicates which channel should be used for deciding about the main mode. A value of zero indicates the switch is not assigned. 0 18 @@ -8669,7 +7361,7 @@ - Position Control switch channel + Position Control switch channel (deprecated) 0 18 @@ -8747,7 +7439,7 @@ - Stabilize switch channel mapping + Stabilize switch channel mapping (deprecated) 0 18 @@ -8804,24 +7496,12 @@ -1 1 - - Threshold for selecting posctl mode - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th - -1 - 1 - Threshold for selecting return to launch mode 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th -1 1 - - Threshold for the stabilize switch - 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th - -1 - 1 - Threshold for the VTOL transition switch 0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channel<th @@ -8845,29 +7525,35 @@ Only climb to at least RTL_DESCEND_ALT above destination. - + Return mode loiter altitude - Descend to this altitude (above destination position) after return, and wait for time defined in RTL_LAND_DELAY. Land (i.e. slowly descend) from this altitude if autolanding allowed. - 2 - 100 + Descend to this altitude (above destination position) after return, and wait for time defined in RTL_LAND_DELAY. Land (i.e. slowly descend) from this altitude if autolanding allowed. VTOLs do transition to hover in this altitdue above the landing point. + 0 m 1 0.5 + + RTL heading mode + Defines the heading behavior during RTL + + Towards next waypoint. + Heading matches destination. + Use current heading. + + Return mode delay Delay before landing (after initial descent) in Return mode. If set to -1 the system will not land but loiter at RTL_DESCEND_ALT. -1 - 300 s 1 0.5 - + Loiter radius for rtl descend Set the radius for loitering to a safe altitude for VTOL transition. 25 - 1000 m 1 0.5 @@ -8876,32 +7562,10 @@ Horizontal radius from return point within which special rules for return mode apply The return altitude will be calculated based on RTL_CONE_ANG parameter. The yaw setpoint will switch to the one defined by corresponding waypoint. 0.5 - 100 - m - 1 - 0.5 - - - Return mode return altitude - Default minimum altitude above destination (e.g. home, safe point, landing pattern) for return flight. This is affected by RTL_MIN_DIST and RTL_CONE_ANG. - 0 - 150 m 1 0.5 - - Return type - Return mode destination and flight path (home location, rally point, mission landing pattern, reverse mission) - - Return to closest safe point (home or rally point) via direct path. - Return to closest safe point other than home (mission landing pattern or rally point), via direct path. If no mission landing or rally points are defined return home via direct path. - Return to a planned mission landing, if available, using the mission path, else return to home via the reverse mission path. Do not consider rally points. - Return via direct path to closest destination: home, start of mission landing pattern or safe point. If the destination is a mission landing pattern, follow the pattern to land. - - - - RTL precision land mode Use precision landing when doing an RTL landing phase. @@ -8911,1507 +7575,368 @@ Required precision landing - - - - Serial Configuration for Roboclaw Driver - Configure on which serial port to run Roboclaw Driver. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - - - - - Address of the Roboclaw - The Roboclaw can be configured to have an address from 0x80 to 0x87, inclusive. It must be configured to match this parameter. - 128 - 135 - - 0x80 - 0x81 - 0x82 - 0x83 - 0x84 - 0x85 - 0x86 - 0x87 - - - - Roboclaw serial baud rate - Baud rate of the serial communication with the Roboclaw. The Roboclaw must be configured to match this rate. - 2400 - 460800 - true - - 2400 baud - 9600 baud - 19200 baud - 38400 baud - 57600 baud - 115200 baud - 230400 baud - 460800 baud - - - - Encoder counts per revolution - Number of encoder counts for one revolution. The roboclaw treats analog encoders (potentiometers) as having 2047 counts per rev. The default value of 1200 corresponds to the default configuration of the Aion R1 rover. - 1 - - - Encoder read period - How long to wait, in Milliseconds, between reading wheel encoder values over Uart from the Roboclaw - 1 - 1000 - ms - - - Uart write period - How long to wait, in Milliseconds, between writing actuator controls over Uart to the Roboclaw - 1 - 1000 - ms - - - - - L1 damping - Damping factor for L1 control. - 0.6 - 0.9 - 2 - 0.05 - - - L1 distance - This is the distance at which the next waypoint is activated. This should be set to about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy). - 1.0 - 50.0 - m - 1 - 0.1 - - - L1 period - This is the L1 distance and defines the tracking point ahead of the rover it's following. Use values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten slowly during tuning until response is sharp without oscillation. - 0.5 - 50.0 - m - 1 - 0.5 - - - Max manual yaw rate - 0.0 - 400 - deg/s - 1 - - - Maximum turn angle for Ackerman steering - At a control output of 0, the steering wheels are at 0 radians. At a control output of 1, the steering wheels are at GND_MAX_ANG radians. - 0.0 - 3.14159 - rad - 3 - 0.01 - - - Speed proportional gain - This is the derivative gain for the speed closed loop controller - 0.00 - 50.0 - %m/s - 3 - 0.005 - - - Speed Integral gain - This is the integral gain for the speed closed loop controller - 0.00 - 50.0 - %m/s - 3 - 0.005 - - - Speed integral maximum value - This is the maxim value the integral can reach to prevent wind-up. - 0.005 - 50.0 - %m/s - 3 - 0.005 - - - Maximum ground speed - 0.0 - 40 - m/s - 1 - 0.5 - - - Speed proportional gain - This is the proportional gain for the speed closed loop controller - 0.005 - 50.0 - %m/s - 3 - 0.005 - - - Speed to throttle scaler - This is a gain to map the speed control output to the throttle linearly. - 0.005 - 50.0 - %m/s - 3 - 0.005 - - - Trim ground speed - 0.0 - 40 - m/s - 1 - 0.5 - - - Control mode for speed - This allows the user to choose between closed loop gps speed or open loop cruise throttle speed - 0 - 1 - - open loop control - close the loop with gps speed - - - - Cruise throttle - This is the throttle setting required to achieve the desired cruise speed. 10% is ok for a traxxas stampede vxl with ESC set to training mode - 0.0 - 1.0 - norm - 2 - 0.01 - - - Throttle limit max - This is the maximum throttle % that can be used by the controller. For a Traxxas stampede vxl with the ESC set to training, 30 % is enough - 0.0 - 1.0 - norm - 2 - 0.01 - - - Throttle limit min - This is the minimum throttle % that can be used by the controller. Set to 0 for rover - 0.0 - 1.0 - norm - 2 - 0.01 - - - Distance from front axle to rear axle - A value of 0.31 is typical for 1/10 RC cars. - 0.0 - m - 3 - 0.01 - - - - - Min airspeed scaling factor for takeoff - Pitch up will be commanded when the following airspeed is reached: FW_AIRSPD_MIN * RWTO_AIRSPD_SCL - 0.0 - 2.0 - norm - 2 - 0.01 - - - Specifies which heading should be held during runnway takeoff - 0: airframe heading, 1: heading towards takeoff waypoint - 0 - 1 - - Airframe - Waypoint - - - - Max pitch during takeoff - Fixed-wing settings are used if set to 0. Note that there is also a minimum pitch of 10 degrees during takeoff, so this must be larger if set. - 0.0 - 60.0 - deg - 1 - 0.5 - - - Max roll during climbout - Roll is limited during climbout to ensure enough lift and prevents aggressive navigation before we're on a safe height. - 0.0 - 60.0 - deg - 1 - 0.5 - - - Max throttle during runway takeoff - Can be used to test taxi on runway - 0.0 - 1.0 - norm - 2 - 0.01 - - - Altitude AGL at which we have enough ground clearance to allow some roll - Until RWTO_NAV_ALT is reached the plane is held level and only rudder is used to keep the heading (see RWTO_HDG). This should be below FW_CLMBOUT_DIFF if FW_CLMBOUT_DIFF > 0. - 0.0 - 100.0 - m - 1 - 1 - - - Pitch setpoint during taxi / before takeoff airspeed is reached - A taildragger with steerable wheel might need to pitch up a little to keep its wheel on the ground before airspeed to takeoff is reached. - -10.0 - 20.0 - deg - 1 - 0.5 - - - Throttle ramp up time for runway takeoff - 1.0 - 15.0 - s - 2 - 0.1 - - - Runway takeoff with landing gear - - - - - Battery-only Logging - When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes. - - - Maximum number of log directories to keep - If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files. - 0 - 1000 - true - - - Mission Log - If enabled, a small additional "mission" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more). - true - - Disabled - All mission messages - Geotagging messages - - - - Logging Mode - Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. - true - - disabled - when armed until disarm (default) - from boot until disarm - from boot until shutdown - depending on AUX1 RC channel - - - - Logging topic profile (integer bitmask) - This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug_*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and Magnetomer data) 7 : Topics for computer vision and collision avoidance 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) - 0 - 1023 - true - - Default set (general log analysis) - Estimator replay (EKF2) - Thermal calibration - System identification - High rate - Debug - Sensor comparison - Computer Vision and Avoidance - Raw FIFO high-rate IMU (Gyro) - Raw FIFO high-rate IMU (Accel) - - - - UTC offset (unit: min) - the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets - -1000 - 1000 - min - - - Log UUID - If set to 1, add an ID to the log, which uniquely identifies the vehicle - - - - - Simulator Battery drain interval - 1 - 86400 - s - 1 - - - Simulator Battery minimal percentage - Can be used to alter the battery level during SITL- or HITL-simulation on the fly. Particularly useful for testing different low-battery behaviour. - 0 - 100 - % - 0.1 - - - - - ID of the Accelerometer that the calibration is for - - - Accelerometer 0 priority - - Uninitialized - Disabled - Min - Low - Medium (Default) - High - Max - - - - Rotation of accelerometer 0 relative to airframe - An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - -1 - 40 - true - - Internal - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - Roll 180° - Roll 180°, Yaw 45° - Roll 180°, Yaw 90° - Roll 180°, Yaw 135° - Pitch 180° - Roll 180°, Yaw 225° - Roll 180°, Yaw 270° - Roll 180°, Yaw 315° - Roll 90° - Roll 90°, Yaw 45° - Roll 90°, Yaw 90° - Roll 90°, Yaw 135° - Roll 270° - Roll 270°, Yaw 45° - Roll 270°, Yaw 90° - Roll 270°, Yaw 135° - Pitch 90° - Pitch 270° - Pitch 180°, Yaw 90° - Pitch 180°, Yaw 270° - Roll 90°, Pitch 90° - Roll 180°, Pitch 90° - Roll 270°, Pitch 90° - Roll 90°, Pitch 180° - Roll 270°, Pitch 180° - Roll 90°, Pitch 270° - Roll 180°, Pitch 270° - Roll 270°, Pitch 270° - Roll 90°, Pitch 180°, Yaw 90° - Roll 90°, Yaw 270° - Roll 90°, Pitch 68°, Yaw 293° - Pitch 315° - Roll 90°, Pitch 315° - - - - Accelerometer calibration temperature - Temperature during last calibration. - celcius - - - Accelerometer X-axis offset - - - Accelerometer X-axis scaling factor - - - Accelerometer Y-axis offset - - - Accelerometer Y-axis scaling factor - - - Accelerometer Z-axis offset - - - Accelerometer Z-axis scaling factor - - - ID of the Accelerometer that the calibration is for - - - Accelerometer 1 priority - - Uninitialized - Disabled - Min - Low - Medium (Default) - High - Max - - - - Rotation of accelerometer 1 relative to airframe - An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - -1 - 40 - true - - Internal - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - Roll 180° - Roll 180°, Yaw 45° - Roll 180°, Yaw 90° - Roll 180°, Yaw 135° - Pitch 180° - Roll 180°, Yaw 225° - Roll 180°, Yaw 270° - Roll 180°, Yaw 315° - Roll 90° - Roll 90°, Yaw 45° - Roll 90°, Yaw 90° - Roll 90°, Yaw 135° - Roll 270° - Roll 270°, Yaw 45° - Roll 270°, Yaw 90° - Roll 270°, Yaw 135° - Pitch 90° - Pitch 270° - Pitch 180°, Yaw 90° - Pitch 180°, Yaw 270° - Roll 90°, Pitch 90° - Roll 180°, Pitch 90° - Roll 270°, Pitch 90° - Roll 90°, Pitch 180° - Roll 270°, Pitch 180° - Roll 90°, Pitch 270° - Roll 180°, Pitch 270° - Roll 270°, Pitch 270° - Roll 90°, Pitch 180°, Yaw 90° - Roll 90°, Yaw 270° - Roll 90°, Pitch 68°, Yaw 293° - Pitch 315° - Roll 90°, Pitch 315° - - - - Accelerometer calibration temperature - Temperature during last calibration. - celcius - - - Accelerometer X-axis offset - - - Accelerometer X-axis scaling factor - - - Accelerometer Y-axis offset - - - Accelerometer Y-axis scaling factor - - - Accelerometer Z-axis offset - - - Accelerometer Z-axis scaling factor - - - ID of the Accelerometer that the calibration is for - - - Accelerometer 2 priority - - Uninitialized - Disabled - Min - Low - Medium (Default) - High - Max - - - - Rotation of accelerometer 2 relative to airframe - An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - -1 - 40 - true - - Internal - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - Roll 180° - Roll 180°, Yaw 45° - Roll 180°, Yaw 90° - Roll 180°, Yaw 135° - Pitch 180° - Roll 180°, Yaw 225° - Roll 180°, Yaw 270° - Roll 180°, Yaw 315° - Roll 90° - Roll 90°, Yaw 45° - Roll 90°, Yaw 90° - Roll 90°, Yaw 135° - Roll 270° - Roll 270°, Yaw 45° - Roll 270°, Yaw 90° - Roll 270°, Yaw 135° - Pitch 90° - Pitch 270° - Pitch 180°, Yaw 90° - Pitch 180°, Yaw 270° - Roll 90°, Pitch 90° - Roll 180°, Pitch 90° - Roll 270°, Pitch 90° - Roll 90°, Pitch 180° - Roll 270°, Pitch 180° - Roll 90°, Pitch 270° - Roll 180°, Pitch 270° - Roll 270°, Pitch 270° - Roll 90°, Pitch 180°, Yaw 90° - Roll 90°, Yaw 270° - Roll 90°, Pitch 68°, Yaw 293° - Pitch 315° - Roll 90°, Pitch 315° - - - - Accelerometer calibration temperature - Temperature during last calibration. - celcius - - - Accelerometer X-axis offset - - - Accelerometer X-axis scaling factor - - - Accelerometer Y-axis offset - - - Accelerometer Y-axis scaling factor - - - Accelerometer Z-axis offset - - - Accelerometer Z-axis scaling factor - - - ID of the Accelerometer that the calibration is for - - - Accelerometer 3 priority - - Uninitialized - Disabled - Min - Low - Medium (Default) - High - Max - - - - Rotation of accelerometer 3 relative to airframe - An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - -1 - 40 - true - - Internal - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - Roll 180° - Roll 180°, Yaw 45° - Roll 180°, Yaw 90° - Roll 180°, Yaw 135° - Pitch 180° - Roll 180°, Yaw 225° - Roll 180°, Yaw 270° - Roll 180°, Yaw 315° - Roll 90° - Roll 90°, Yaw 45° - Roll 90°, Yaw 90° - Roll 90°, Yaw 135° - Roll 270° - Roll 270°, Yaw 45° - Roll 270°, Yaw 90° - Roll 270°, Yaw 135° - Pitch 90° - Pitch 270° - Pitch 180°, Yaw 90° - Pitch 180°, Yaw 270° - Roll 90°, Pitch 90° - Roll 180°, Pitch 90° - Roll 270°, Pitch 90° - Roll 90°, Pitch 180° - Roll 270°, Pitch 180° - Roll 90°, Pitch 270° - Roll 180°, Pitch 270° - Roll 270°, Pitch 270° - Roll 90°, Pitch 180°, Yaw 90° - Roll 90°, Yaw 270° - Roll 90°, Pitch 68°, Yaw 293° - Pitch 315° - Roll 90°, Pitch 315° - - - - Accelerometer calibration temperature - Temperature during last calibration. - celcius - - - Accelerometer X-axis offset - - - Accelerometer X-axis scaling factor - - - Accelerometer Y-axis offset - - - Accelerometer Y-axis scaling factor - - - Accelerometer Z-axis offset - - - Accelerometer Z-axis scaling factor - - - ID of the Gyro that the calibration is for - - - Gyro 0 priority - - Uninitialized - Disabled - Min - Low - Medium (Default) - High - Max - - - - Rotation of gyro 0 relative to airframe - An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - -1 - 40 - true - - Internal - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - Roll 180° - Roll 180°, Yaw 45° - Roll 180°, Yaw 90° - Roll 180°, Yaw 135° - Pitch 180° - Roll 180°, Yaw 225° - Roll 180°, Yaw 270° - Roll 180°, Yaw 315° - Roll 90° - Roll 90°, Yaw 45° - Roll 90°, Yaw 90° - Roll 90°, Yaw 135° - Roll 270° - Roll 270°, Yaw 45° - Roll 270°, Yaw 90° - Roll 270°, Yaw 135° - Pitch 90° - Pitch 270° - Pitch 180°, Yaw 90° - Pitch 180°, Yaw 270° - Roll 90°, Pitch 90° - Roll 180°, Pitch 90° - Roll 270°, Pitch 90° - Roll 90°, Pitch 180° - Roll 270°, Pitch 180° - Roll 90°, Pitch 270° - Roll 180°, Pitch 270° - Roll 270°, Pitch 270° - Roll 90°, Pitch 180°, Yaw 90° - Roll 90°, Yaw 270° - Roll 90°, Pitch 68°, Yaw 293° - Pitch 315° - Roll 90°, Pitch 315° - - - - Gyroscope calibration temperature - Temperature during last calibration. - celcius - - - Gyro X-axis offset - - - Gyro Y-axis offset - - - Gyro Z-axis offset - - - ID of the Gyro that the calibration is for - - - Gyro 1 priority - - Uninitialized - Disabled - Min - Low - Medium (Default) - High - Max - - - - Rotation of gyro 1 relative to airframe - An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - -1 - 40 - true - - Internal - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - Roll 180° - Roll 180°, Yaw 45° - Roll 180°, Yaw 90° - Roll 180°, Yaw 135° - Pitch 180° - Roll 180°, Yaw 225° - Roll 180°, Yaw 270° - Roll 180°, Yaw 315° - Roll 90° - Roll 90°, Yaw 45° - Roll 90°, Yaw 90° - Roll 90°, Yaw 135° - Roll 270° - Roll 270°, Yaw 45° - Roll 270°, Yaw 90° - Roll 270°, Yaw 135° - Pitch 90° - Pitch 270° - Pitch 180°, Yaw 90° - Pitch 180°, Yaw 270° - Roll 90°, Pitch 90° - Roll 180°, Pitch 90° - Roll 270°, Pitch 90° - Roll 90°, Pitch 180° - Roll 270°, Pitch 180° - Roll 90°, Pitch 270° - Roll 180°, Pitch 270° - Roll 270°, Pitch 270° - Roll 90°, Pitch 180°, Yaw 90° - Roll 90°, Yaw 270° - Roll 90°, Pitch 68°, Yaw 293° - Pitch 315° - Roll 90°, Pitch 315° - - - - Gyroscope calibration temperature - Temperature during last calibration. - celcius - - - Gyro X-axis offset - - - Gyro Y-axis offset - - - Gyro Z-axis offset - - - ID of the Gyro that the calibration is for - - - Gyro 2 priority - - Uninitialized - Disabled - Min - Low - Medium (Default) - High - Max - - - - Rotation of gyro 2 relative to airframe - An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - -1 - 40 - true - - Internal - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - Roll 180° - Roll 180°, Yaw 45° - Roll 180°, Yaw 90° - Roll 180°, Yaw 135° - Pitch 180° - Roll 180°, Yaw 225° - Roll 180°, Yaw 270° - Roll 180°, Yaw 315° - Roll 90° - Roll 90°, Yaw 45° - Roll 90°, Yaw 90° - Roll 90°, Yaw 135° - Roll 270° - Roll 270°, Yaw 45° - Roll 270°, Yaw 90° - Roll 270°, Yaw 135° - Pitch 90° - Pitch 270° - Pitch 180°, Yaw 90° - Pitch 180°, Yaw 270° - Roll 90°, Pitch 90° - Roll 180°, Pitch 90° - Roll 270°, Pitch 90° - Roll 90°, Pitch 180° - Roll 270°, Pitch 180° - Roll 90°, Pitch 270° - Roll 180°, Pitch 270° - Roll 270°, Pitch 270° - Roll 90°, Pitch 180°, Yaw 90° - Roll 90°, Yaw 270° - Roll 90°, Pitch 68°, Yaw 293° - Pitch 315° - Roll 90°, Pitch 315° - - - - Gyroscope calibration temperature - Temperature during last calibration. - celcius - - - Gyro X-axis offset - - - Gyro Y-axis offset - - - Gyro Z-axis offset - - - ID of the Gyro that the calibration is for - - - Gyro 3 priority - - Uninitialized - Disabled - Min - Low - Medium (Default) - High - Max - - - - Rotation of gyro 3 relative to airframe - An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - -1 - 40 - true - - Internal - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - Roll 180° - Roll 180°, Yaw 45° - Roll 180°, Yaw 90° - Roll 180°, Yaw 135° - Pitch 180° - Roll 180°, Yaw 225° - Roll 180°, Yaw 270° - Roll 180°, Yaw 315° - Roll 90° - Roll 90°, Yaw 45° - Roll 90°, Yaw 90° - Roll 90°, Yaw 135° - Roll 270° - Roll 270°, Yaw 45° - Roll 270°, Yaw 90° - Roll 270°, Yaw 135° - Pitch 90° - Pitch 270° - Pitch 180°, Yaw 90° - Pitch 180°, Yaw 270° - Roll 90°, Pitch 90° - Roll 180°, Pitch 90° - Roll 270°, Pitch 90° - Roll 90°, Pitch 180° - Roll 270°, Pitch 180° - Roll 90°, Pitch 270° - Roll 180°, Pitch 270° - Roll 270°, Pitch 270° - Roll 90°, Pitch 180°, Yaw 90° - Roll 90°, Yaw 270° - Roll 90°, Pitch 68°, Yaw 293° - Pitch 315° - Roll 90°, Pitch 315° - - - - Gyroscope calibration temperature - Temperature during last calibration. - celcius - - - Gyro X-axis offset - - - Gyro Y-axis offset - - - Gyro Z-axis offset - - - ID of Magnetometer the calibration is for - - - Mag 0 priority - - Uninitialized - Disabled - Min - Low - Medium (Default) - High - Max - - - - Rotation of magnetometer 0 relative to airframe - An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - -1 - 40 - true - - Internal - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - Roll 180° - Roll 180°, Yaw 45° - Roll 180°, Yaw 90° - Roll 180°, Yaw 135° - Pitch 180° - Roll 180°, Yaw 225° - Roll 180°, Yaw 270° - Roll 180°, Yaw 315° - Roll 90° - Roll 90°, Yaw 45° - Roll 90°, Yaw 90° - Roll 90°, Yaw 135° - Roll 270° - Roll 270°, Yaw 45° - Roll 270°, Yaw 90° - Roll 270°, Yaw 135° - Pitch 90° - Pitch 270° - Pitch 180°, Yaw 90° - Pitch 180°, Yaw 270° - Roll 90°, Pitch 90° - Roll 180°, Pitch 90° - Roll 270°, Pitch 90° - Roll 90°, Pitch 180° - Roll 270°, Pitch 180° - Roll 90°, Pitch 270° - Roll 180°, Pitch 270° - Roll 270°, Pitch 270° - Roll 90°, Pitch 180°, Yaw 90° - Roll 90°, Yaw 270° - Roll 90°, Pitch 68°, Yaw 293° - Pitch 315° - Roll 90°, Pitch 315° - - - - Magnetometer calibration temperature - Temperature during last calibration. - celcius - - - X Axis throttle compensation for Mag 0 - Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] - - - Magnetometer X-axis off diagonal factor - - - Magnetometer X-axis offset - - - Magnetometer X-axis scaling factor - - - Y Axis throttle compensation for Mag 0 - Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] - - - Magnetometer Y-axis off diagonal factor - - - Magnetometer Y-axis offset - - - Magnetometer Y-axis scaling factor - - - Z Axis throttle compensation for Mag 0 - Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] - - - Magnetometer Z-axis off diagonal factor - - - Magnetometer Z-axis offset - - - Magnetometer Z-axis scaling factor - - - ID of Magnetometer the calibration is for - - - Mag 1 priority - - Uninitialized - Disabled - Min - Low - Medium (Default) - High - Max - - - - Rotation of magnetometer 1 relative to airframe - An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - -1 - 40 - true - - Internal - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - Roll 180° - Roll 180°, Yaw 45° - Roll 180°, Yaw 90° - Roll 180°, Yaw 135° - Pitch 180° - Roll 180°, Yaw 225° - Roll 180°, Yaw 270° - Roll 180°, Yaw 315° - Roll 90° - Roll 90°, Yaw 45° - Roll 90°, Yaw 90° - Roll 90°, Yaw 135° - Roll 270° - Roll 270°, Yaw 45° - Roll 270°, Yaw 90° - Roll 270°, Yaw 135° - Pitch 90° - Pitch 270° - Pitch 180°, Yaw 90° - Pitch 180°, Yaw 270° - Roll 90°, Pitch 90° - Roll 180°, Pitch 90° - Roll 270°, Pitch 90° - Roll 90°, Pitch 180° - Roll 270°, Pitch 180° - Roll 90°, Pitch 270° - Roll 180°, Pitch 270° - Roll 270°, Pitch 270° - Roll 90°, Pitch 180°, Yaw 90° - Roll 90°, Yaw 270° - Roll 90°, Pitch 68°, Yaw 293° - Pitch 315° - Roll 90°, Pitch 315° + + Return mode return altitude + Default minimum altitude above destination (e.g. home, safe point, landing pattern) for return flight. The vehicle will climb to this altitude when Return mode is enganged, unless it currently is flying higher already. This is affected by RTL_MIN_DIST and RTL_CONE_ANG. + 0 + m + 1 + 0.5 + + + Return type + Return mode destination and flight path (home location, rally point, mission landing pattern, reverse mission) + + Return to closest safe point (home or rally point) via direct path. + Return to closest safe point other than home (mission landing pattern or rally point), via direct path. If no mission landing or rally points are defined return home via direct path. Always chose closest safe landing point if vehicle is a VTOL in hover mode. + Return to a planned mission landing, if available, using the mission path, else return to home via the reverse mission path. Do not consider rally points. + Return via direct path to closest destination: home, start of mission landing pattern or safe point. If the destination is a mission landing pattern, follow the pattern to land. - - Magnetometer calibration temperature - Temperature during last calibration. - celcius + + + + RTL time estimate safety margin factor + Safety factor that is used to scale the actual RTL time estimate. Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN + 1.0 + 2.0 + 1 + 0.1 - - X Axis throttle compensation for Mag 1 - Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] + + RTL time estimate safety margin offset + Margin that is added to the time estimate, after it has already been scaled Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN + 0 + 3600 + s + 1 + 1 - - Magnetometer X-axis off diagonal factor + + + + L1 damping + Damping factor for L1 control. + 0.6 + 0.9 + 2 + 0.05 - - Magnetometer X-axis offset + + L1 distance + This is the distance at which the next waypoint is activated. This should be set to about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy). + 1.0 + 50.0 + m + 1 + 0.1 - - Magnetometer X-axis scaling factor + + L1 period + This is the L1 distance and defines the tracking point ahead of the rover it's following. Use values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten slowly during tuning until response is sharp without oscillation. + 0.5 + 50.0 + m + 1 + 0.5 - - Y Axis throttle compensation for Mag 1 - Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] + + Max manual yaw rate + 0.0 + 400 + deg/s + 1 - - Magnetometer Y-axis off diagonal factor + + Maximum turn angle for Ackerman steering + At a control output of 0, the steering wheels are at 0 radians. At a control output of 1, the steering wheels are at GND_MAX_ANG radians. + 0.0 + 3.14159 + rad + 3 + 0.01 - - Magnetometer Y-axis offset + + Speed proportional gain + This is the derivative gain for the speed closed loop controller + 0.00 + 50.0 + %m/s + 3 + 0.005 - - Magnetometer Y-axis scaling factor + + Speed Integral gain + This is the integral gain for the speed closed loop controller + 0.00 + 50.0 + %m/s + 3 + 0.005 - - Z Axis throttle compensation for Mag 1 - Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] + + Speed integral maximum value + This is the maxim value the integral can reach to prevent wind-up. + 0.005 + 50.0 + %m/s + 3 + 0.005 - - Magnetometer Z-axis off diagonal factor + + Maximum ground speed + 0.0 + 40 + m/s + 1 + 0.5 - - Magnetometer Z-axis offset + + Speed proportional gain + This is the proportional gain for the speed closed loop controller + 0.005 + 50.0 + %m/s + 3 + 0.005 - - Magnetometer Z-axis scaling factor + + Speed to throttle scaler + This is a gain to map the speed control output to the throttle linearly. + 0.005 + 50.0 + %m/s + 3 + 0.005 - - ID of Magnetometer the calibration is for + + Trim ground speed + 0.0 + 40 + m/s + 1 + 0.5 - - Mag 2 priority + + Control mode for speed + This allows the user to choose between closed loop gps speed or open loop cruise throttle speed + 0 + 1 - Uninitialized - Disabled - Min - Low - Medium (Default) - High - Max + open loop control + close the loop with gps speed - - Rotation of magnetometer 2 relative to airframe - An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - -1 - 40 - true + + Cruise throttle + This is the throttle setting required to achieve the desired cruise speed. 10% is ok for a traxxas stampede vxl with ESC set to training mode + 0.0 + 1.0 + norm + 2 + 0.01 + + + Throttle limit max + This is the maximum throttle % that can be used by the controller. For a Traxxas stampede vxl with the ESC set to training, 30 % is enough + 0.0 + 1.0 + norm + 2 + 0.01 + + + Throttle limit min + This is the minimum throttle % that can be used by the controller. Set to 0 for rover + 0.0 + 1.0 + norm + 2 + 0.01 + + + Distance from front axle to rear axle + A value of 0.31 is typical for 1/10 RC cars. + 0.0 + m + 3 + 0.01 + + + + + Specifies which heading should be held during the runway takeoff ground roll + 0: airframe heading when takeoff is initiated 1: position control along runway direction (bearing defined from vehicle position on takeoff initiation to MAV_CMD_TAKEOFF position defined by operator) + 0 + 1 - Internal - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - Roll 180° - Roll 180°, Yaw 45° - Roll 180°, Yaw 90° - Roll 180°, Yaw 135° - Pitch 180° - Roll 180°, Yaw 225° - Roll 180°, Yaw 270° - Roll 180°, Yaw 315° - Roll 90° - Roll 90°, Yaw 45° - Roll 90°, Yaw 90° - Roll 90°, Yaw 135° - Roll 270° - Roll 270°, Yaw 45° - Roll 270°, Yaw 90° - Roll 270°, Yaw 135° - Pitch 90° - Pitch 270° - Pitch 180°, Yaw 90° - Pitch 180°, Yaw 270° - Roll 90°, Pitch 90° - Roll 180°, Pitch 90° - Roll 270°, Pitch 90° - Roll 90°, Pitch 180° - Roll 270°, Pitch 180° - Roll 90°, Pitch 270° - Roll 180°, Pitch 270° - Roll 270°, Pitch 270° - Roll 90°, Pitch 180°, Yaw 90° - Roll 90°, Yaw 270° - Roll 90°, Pitch 68°, Yaw 293° - Pitch 315° - Roll 90°, Pitch 315° + Airframe + Runway - - Magnetometer calibration temperature - Temperature during last calibration. - celcius - - - X Axis throttle compensation for Mag 2 - Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] + + Max throttle during runway takeoff + 0.0 + 1.0 + norm + 2 + 0.01 - - Magnetometer X-axis off diagonal factor + + NPFG period while steering on runway + 1.0 + 100.0 + s + 1 + 0.1 - - Magnetometer X-axis offset + + Enable use of yaw stick for nudging the wheel during runway ground roll + This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course. Particularly useful for skinny runways or if the wheel servo is a bit off trim. - - Magnetometer X-axis scaling factor + + Pitch setpoint during taxi / before takeoff rotation airspeed is reached + A taildragger with steerable wheel might need to pitch up a little to keep its wheel on the ground before airspeed to takeoff is reached. + -10.0 + 20.0 + deg + 1 + 0.5 - - Y Axis throttle compensation for Mag 2 - Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] + + Throttle ramp up time for runway takeoff + 1.0 + 15.0 + s + 2 + 0.1 - - Magnetometer Y-axis off diagonal factor + + Takeoff rotation airspeed + The calibrated airspeed threshold during the takeoff ground roll when the plane should start rotating (pitching up). Must be less than the takeoff airspeed, will otherwise be capped at the takeoff airpeed (see FW_TKO_AIRSPD). If set <= 0.0, defaults to 0.9 * takeoff airspeed (see FW_TKO_AIRSPD) + -1.0 + m/s + 1 + 0.1 - - Magnetometer Y-axis offset + + Takeoff rotation time + This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation + 0.1 + s + 1 + 0.1 - - Magnetometer Y-axis scaling factor + + Runway takeoff with landing gear - - Z Axis throttle compensation for Mag 2 - Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] + + + + Logfile Encryption algorithm + Selects the algorithm used for logfile encryption + + Disabled + XChaCha20 + AES + - - Magnetometer Z-axis off diagonal factor + + Battery-only Logging + When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes. - - Magnetometer Z-axis offset + + Maximum number of log directories to keep + If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files. + 0 + 1000 + true - - Magnetometer Z-axis scaling factor + + Logfile Encryption key exchange key + If the logfile is encrypted using a symmetric key algorithm, the used encryption key is generated at logging start and stored on the sdcard RSA2048 encrypted using this key. + 0 + 255 - - ID of Magnetometer the calibration is for + + Logfile Encryption key index + Selects the key in keystore, used for encrypting the log. When using a symmetric encryption algorithm, the key is generated at logging start and kept stored in this index. For symmetric algorithms, the key is volatile and valid only for the duration of logging. The key is stored in encrypted format on the sdcard alongside the logfile, using an RSA2048 key defined by the SDLOG_EXCHANGE_KEY + 0 + 255 - - Mag 3 priority + + Mission Log + If enabled, a small additional "mission" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more). + true - Uninitialized - Disabled - Min - Low - Medium (Default) - High - Max + Disabled + All mission messages + Geotagging messages - - Rotation of magnetometer 3 relative to airframe - An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. - -1 - 40 + + Logging Mode + Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. true - Internal - No rotation - Yaw 45° - Yaw 90° - Yaw 135° - Yaw 180° - Yaw 225° - Yaw 270° - Yaw 315° - Roll 180° - Roll 180°, Yaw 45° - Roll 180°, Yaw 90° - Roll 180°, Yaw 135° - Pitch 180° - Roll 180°, Yaw 225° - Roll 180°, Yaw 270° - Roll 180°, Yaw 315° - Roll 90° - Roll 90°, Yaw 45° - Roll 90°, Yaw 90° - Roll 90°, Yaw 135° - Roll 270° - Roll 270°, Yaw 45° - Roll 270°, Yaw 90° - Roll 270°, Yaw 135° - Pitch 90° - Pitch 270° - Pitch 180°, Yaw 90° - Pitch 180°, Yaw 270° - Roll 90°, Pitch 90° - Roll 180°, Pitch 90° - Roll 270°, Pitch 90° - Roll 90°, Pitch 180° - Roll 270°, Pitch 180° - Roll 90°, Pitch 270° - Roll 180°, Pitch 270° - Roll 270°, Pitch 270° - Roll 90°, Pitch 180°, Yaw 90° - Roll 90°, Yaw 270° - Roll 90°, Pitch 68°, Yaw 293° - Pitch 315° - Roll 90°, Pitch 315° + disabled + when armed until disarm (default) + from boot until disarm + from boot until shutdown + depending on AUX1 RC channel + from 1st armed until shutdown - - Magnetometer calibration temperature - Temperature during last calibration. - celcius - - - X Axis throttle compensation for Mag 3 - Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] - - - Magnetometer X-axis off diagonal factor - - - Magnetometer X-axis offset - - - Magnetometer X-axis scaling factor - - - Y Axis throttle compensation for Mag 3 - Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] - - - Magnetometer Y-axis off diagonal factor - - - Magnetometer Y-axis offset - - - Magnetometer Y-axis scaling factor + + Logging topic profile (integer bitmask) + This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug_*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) 7 : Topics for computer vision and collision avoidance 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging) + 0 + 2047 + true + + Default set (general log analysis) + Estimator replay (EKF2) + Thermal calibration + System identification + High rate + Debug + Sensor comparison + Computer Vision and Avoidance + Raw FIFO high-rate IMU (Gyro) + Raw FIFO high-rate IMU (Accel) + Mavlink tunnel message logging + - - Z Axis throttle compensation for Mag 3 - Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] + + UTC offset (unit: min) + the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets + -1000 + 1000 + min - - Magnetometer Z-axis off diagonal factor + + Log UUID + If set to 1, add an ID to the log, which uniquely identifies the vehicle - - Magnetometer Z-axis offset + + + + Simulator Battery drain interval + 1 + 86400 + s + 1 - - Magnetometer Z-axis scaling factor + + Simulator Battery minimal percentage + Can be used to alter the battery level during SITL- or HITL-simulation on the fly. Particularly useful for testing different low-battery behaviour. + 0 + 100 + % + 0.1 + + Type of magnetometer compensation @@ -10429,23 +7954,23 @@ Differential pressure sensor offset The offset (zero-reading) in Pascal - + Maximum height above ground when reliant on optical flow This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably. The height setpoint will be limited to be no greater than this value when the navigation system is completely reliant on optical flow data and the height above ground estimate is valid. The sensor may be usable above this height, but accuracy will progressively degrade. 1.0 - 25.0 + 100.0 m 1 0.1 - + Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground is less than 50% of this value. 1.0 rad/s 2 - + Minimum height above ground when reliant on optical flow This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably. The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus. 0.0 @@ -10456,6 +7981,11 @@ + + Enable external ADS1115 ADC + If enabled, the internal ADC is not used. + true + Capacity/current multiplier for high-current capable SMBUS battery 1 @@ -10510,20 +8040,9 @@ 2.00 m - - Automatically set external rotations - During calibration attempt to automatically determine the rotation of external magnetometers. - - - Bitfield selecting mag sides for calibration - If set to two side calibration, only the offsets are estimated, the scale calibration is left unchanged. Thus an initial six side calibration is recommended. Bits: ORIENTATION_TAIL_DOWN = 1 ORIENTATION_NOSE_DOWN = 2 ORIENTATION_LEFT = 4 ORIENTATION_RIGHT = 8 ORIENTATION_UPSIDE_DOWN = 16 ORIENTATION_RIGHTSIDE_UP = 32 - 34 - 63 - - Two side calibration - Three side calibration - Six side calibration - + + For legacy QGC support only + Use SENS_MAG_SIDES instead Low pass filter cutoff frequency for accel @@ -10553,7 +8072,14 @@ Hz true - + + IMU gyro ESC notch filter bandwidth + Bandwidth per notch filter when using dynamic notch filtering with ESC RPM. + 5 + 30 + Hz + + IMU gyro dynamic notch filtering Enable bank of dynamically updating notch filters. Requires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN). 0 @@ -10563,6 +8089,17 @@ FFT + + IMU gyro dynamic notch filter harmonics + ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering. + 1 + 7 + + + IMU gyro dynamic notch filter minimum frequency + Minimum notch filter frequency in Hz. + Hz + IMU gyro FFT enable true @@ -10578,31 +8115,52 @@ 4096 - + IMU gyro FFT maximum frequency 1 1000 Hz true - + IMU gyro FFT minimum frequency 1 1000 Hz true - + + IMU gyro FFT SNR + 1 + 30 + + Notch filter bandwidth for gyro - The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See "IMU_GYRO_NF_FREQ" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers. + The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See "IMU_GYRO_NF0_FRQ" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers. 0 100 Hz true - + Notch filter frequency for gyro - The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See "IMU_GYRO_NF_BW" to set the bandwidth of the filter. A value of 0 disables the filter. + The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See "IMU_GYRO_NF0_BW" to set the bandwidth of the filter. A value of 0 disables the filter. + 0 + 1000 + Hz + true + + + Notch filter 1 bandwidth for gyro + The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See "IMU_GYRO_NF1_FRQ" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers. + 0 + 100 + Hz + true + + + Notch filter 2 frequency for gyro + The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See "IMU_GYRO_NF1_BW" to set the bandwidth of the filter. A value of 0 disables the filter. 0 1000 Hz @@ -10638,6 +8196,41 @@ 400 Hz + + INA220 Power Monitor Config + 0 + 65535 + 1 + 1 + + + INA220 Power Monitor Battery Max Current + 0.1 + 500.0 + 2 + 0.1 + + + INA220 Power Monitor Regulator Max Current + 0.1 + 500.0 + 2 + 0.1 + + + INA220 Power Monitor Battery Shunt + 0.000000001 + 0.1 + 10 + .000000001 + + + INA220 Power Monitor Regulator Shunt + 0.000000001 + 0.1 + 10 + .000000001 + INA226 Power Monitor Config 0 @@ -10680,13 +8273,19 @@ 10 .000000001 - - PCF8583 rotorfreq (i2c) i2c address - true - - Address 0x50 (80) - Address 0x51 (81) - + + INA238 Power Monitor Max Current + 0.1 + 327.68 + 2 + 0.1 + + + INA238 Power Monitor Shunt + 0.000000001 + 0.1 + 10 + .000000001 PCF8583 rotorfreq (i2c) pulse count @@ -10702,23 +8301,60 @@ PCF8583 rotorfreq (i2c) pulse reset value - Internal device counter is reset to 0 when overun this value, counter is able to store upto 6 digits reset of counter takes some time - measurement with reset has worse accurancy. 0 means reset counter after every measurement. + Internal device counter is reset to 0 when overrun this value, counter is able to store up to 6 digits reset of counter takes some time - measurement with reset has worse accuracy. 0 means reset counter after every measurement. true + + AFBR Rangefinder Short/Long Range Threshold Hysteresis + This parameter defines the hysteresis for switching between short and long range mode. + 1 + 10 + m + + + AFBR Rangefinder Long Range Rate + This parameter defines measurement rate of the AFBR Rangefinder in long range mode. + 1 + 100 + + + AFBR Rangefinder Mode + This parameter defines the mode of the AFBR Rangefinder. + 0 + 3 + true + + Short Range Mode + Long Range Mode + High Speed Short Range Mode + High Speed Long Range Mode + + + + AFBR Rangefinder Short Range Rate + This parameter defines measurement rate of the AFBR Rangefinder in short range mode. + 1 + 100 + + + AFBR Rangefinder Short/Long Range Threshold + This parameter defines the threshold for switching between short and long range mode. The mode will switch from short to long range when the distance is greater than the threshold plus the hysteresis. The mode will switch from long to short range when the distance is less than the threshold minus the hysteresis. + 1 + 50 + m + QNH for barometer 500 1500 hPa - true Baro max rate - Barometric air data maximum publication rate. This is an upper bound, actual barometric data rate is still dependant on the sensor. + Barometric air data maximum publication rate. This is an upper bound, actual barometric data rate is still dependent on the sensor. 1 200 Hz - true Board rotation @@ -10785,39 +8421,36 @@ This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user to fine tune the board offset in the event of misalignment. deg - - Serial Configuration for Lanbao PSK-CM8JL65-CC5 - Configure on which serial port to run Lanbao PSK-CM8JL65-CC5. + + Analog Devices ADIS16448 IMU (external SPI) + 0 + 1 true Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - - - Distance Sensor Rotation - Distance Sensor Rotation as MAV_SENSOR_ORIENTATION enum - True - - ROTATION_FORWARD_FACING - ROTATION_RIGHT_FACING - ROTATION_LEFT_FACING - ROTATION_BACKWARD_FACING - ROTATION_UPWARD_FACING - ROTATION_DOWNWARD_FACING + Enabled - - Analog Devices ADIS16448 IMU (external SPI) + + Analog Devices ADIS16507 IMU (external SPI) + true + + + Enable simulated airspeed sensor instance + 0 + 1 + true + + Disabled + Enabled + + + + ASP5033 differential pressure sensor (external I2C) + true + + + Enable simulated barometer sensor instance 0 1 true @@ -10834,6 +8467,21 @@ Eagle Tree airspeed sensor (external I2C) true + + Enable simulated GPS sinstance + 0 + 1 + true + + Disabled + Enabled + + + + Enable INA220 Power Monitor + For systems a INA220 Power Monitor, this should be set to true + true + Enable INA226 Power Monitor For systems a INA226 Power Monitor, this should be set to true @@ -10844,15 +8492,34 @@ For systems a INA228 Power Monitor, this should be set to true true + + Enable INA238 Power Monitor + For systems a INA238 Power Monitor, this should be set to true + true + + + IR-LOCK Sensor (external I2C) + true + Lidar-Lite (LL40LS) 0 - 2 + 2 + true + + Disabled + PWM + I2C + + + + Enable simulated magnetometer sensor instance + 0 + 1 true Disabled - PWM - I2C + Enabled @@ -10869,17 +8536,36 @@ Autodetect - - TE MS4525 differential pressure sensor (external I2C) + + TE MS4515 differential pressure sensor (external I2C) + true + + + TE MS4525DO differential pressure sensor (external I2C) + true + + + TE MS5525DSO differential pressure sensor (external I2C) true - - TE MS5525 differential pressure sensor (external I2C) + + PAA3905 Optical Flow true - PAW3902 & PAW3903 Optical Flow + PAW3902/PAW3903 Optical Flow + true + + + PCF8583 eneable driver + Run PCF8583 driver automatically + 0 + 1 true + + Disabled + Eneabled + PGA460 Ultrasonic driver (PGA460) @@ -10906,6 +8592,9 @@ SF10/b SF10/c SF11/c + SF30/b + SF30/c + LW20/c @@ -10921,12 +8610,25 @@ SF11/c SF/LW20/b SF/LW20/c + SF/LW30/d + + SHT3x temperature and hygrometer + true + + + Goertek SPL06 Barometer (external I2C) + true + HY-SRF05 / HC-SR05 true + + TF02 Pro Distance Sensor (i2c) + true + Thermal control of sensor temperature @@ -10949,6 +8651,10 @@ TREvo3m + + VL53L0X Distance Sensor + true + VL53L1X Distance Sensor true @@ -10957,10 +8663,17 @@ External I2C probe Probe for optional external I2C devices. - - PX4Flow board rotation - This parameter defines the yaw rotation of the PX4FLOW board relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle. The recommneded installation default for the PX4FLOW board is with the Y axis forward (270 deg yaw). + + Optical flow max rate + Optical flow data maximum publication rate. This is an upper bound, actual optical flow data rate is still dependent on the sensor. + 1 + 200 + Hz true + + + Optical flow rotation + This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle. No rotation Yaw 45° @@ -10972,7 +8685,7 @@ Yaw 315° - + Multi GPS Blending Control Mask Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. 0 : Set to true to use speed accuracy 1 : Set to true to use horizontal position accuracy 2 : Set to true to use vertical position accuracy 0 @@ -10997,6 +8710,10 @@ s 1 + + IMU auto calibration + Automatically initialize IMU (accel/gyro) calibration from bias estimates if available. + Sensors hub IMU mode true @@ -11038,23 +8755,13 @@ For systems with an external barometer, this should be set to false to make sure that the external is used. true - - Serial Configuration for LeddarOne Rangefinder - Configure on which serial port to run LeddarOne Rangefinder. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - + + Magnetometer auto calibration + Automatically initialize magnetometer calibration from bias estimate if available. + + + Automatically set external rotations + During calibration attempt to automatically determine the rotation of external magnetometers. Sensors hub mag mode @@ -11064,14 +8771,25 @@ Publish primary magnetometer - + Magnetometer max rate - Magnetometer data maximum publication rate. This is an upper bound, actual magnetometer data rate is still dependant on the sensor. + Magnetometer data maximum publication rate. This is an upper bound, actual magnetometer data rate is still dependent on the sensor. 1 200 Hz true + + Bitfield selecting mag sides for calibration + If set to two side calibration, only the offsets are estimated, the scale calibration is left unchanged. Thus an initial six side calibration is recommended. Bits: ORIENTATION_TAIL_DOWN = 1 ORIENTATION_NOSE_DOWN = 2 ORIENTATION_LEFT = 4 ORIENTATION_RIGHT = 8 ORIENTATION_UPSIDE_DOWN = 16 ORIENTATION_RIGHTSIDE_UP = 32 + 34 + 63 + + Two side calibration + Three side calibration + Six side calibration + + MaxBotix MB12XX Sensor 0 Rotation This parameter defines the rotation of the sensor relative to the platform. @@ -11490,79 +9208,17 @@ ROTATION_YAW_180 - - Serial Configuration for Lightware Laser Rangefinder (serial) - Configure on which serial port to run Lightware Laser Rangefinder (serial). - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - Target IMU device ID to regulate temperature - - Serial Configuration for ThoneFlow-3901U optical flow sensor - Configure on which serial port to run ThoneFlow-3901U optical flow sensor. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - - - Serial Configuration for Benewake TFmini Rangefinder - Configure on which serial port to run Benewake TFmini Rangefinder. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - - - Serial Configuration for uLanding Radar - Configure on which serial port to run uLanding Radar. + + Dynamically simulate failure of airspeed sensor instance + 0 + 1 true Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port + Enabled @@ -11583,363 +9239,30 @@ - - Serial Configuration for RC Input Driver - Configure on which serial port to run RC Input Driver. Setting this to 'Disabled' will use a board-specific default port for RC input. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - - - Baudrate for the GPS 1 Serial Port - Configure the Baudrate for the GPS 1 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. - true - - Auto - 50 8N1 - 75 8N1 - 110 8N1 - 134 8N1 - 150 8N1 - 200 8N1 - 300 8N1 - 600 8N1 - 1200 8N1 - 1800 8N1 - 2400 8N1 - 4800 8N1 - 9600 8N1 - 19200 8N1 - 38400 8N1 - 57600 8N1 - 115200 8N1 - 230400 8N1 - 460800 8N1 - 500000 8N1 - 921600 8N1 - 1000000 8N1 - 1500000 8N1 - 2000000 8N1 - 3000000 8N1 - - - - Baudrate for the GPS 2 Serial Port - Configure the Baudrate for the GPS 2 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. - true - - Auto - 50 8N1 - 75 8N1 - 110 8N1 - 134 8N1 - 150 8N1 - 200 8N1 - 300 8N1 - 600 8N1 - 1200 8N1 - 1800 8N1 - 2400 8N1 - 4800 8N1 - 9600 8N1 - 19200 8N1 - 38400 8N1 - 57600 8N1 - 115200 8N1 - 230400 8N1 - 460800 8N1 - 500000 8N1 - 921600 8N1 - 1000000 8N1 - 1500000 8N1 - 2000000 8N1 - 3000000 8N1 - - - - Baudrate for the GPS 3 Serial Port - Configure the Baudrate for the GPS 3 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. - true - - Auto - 50 8N1 - 75 8N1 - 110 8N1 - 134 8N1 - 150 8N1 - 200 8N1 - 300 8N1 - 600 8N1 - 1200 8N1 - 1800 8N1 - 2400 8N1 - 4800 8N1 - 9600 8N1 - 19200 8N1 - 38400 8N1 - 57600 8N1 - 115200 8N1 - 230400 8N1 - 460800 8N1 - 500000 8N1 - 921600 8N1 - 1000000 8N1 - 1500000 8N1 - 2000000 8N1 - 3000000 8N1 - - - - Baudrate for the Radio Controller Serial Port - Configure the Baudrate for the Radio Controller Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. - true - - Auto - 50 8N1 - 75 8N1 - 110 8N1 - 134 8N1 - 150 8N1 - 200 8N1 - 300 8N1 - 600 8N1 - 1200 8N1 - 1800 8N1 - 2400 8N1 - 4800 8N1 - 9600 8N1 - 19200 8N1 - 38400 8N1 - 57600 8N1 - 115200 8N1 - 230400 8N1 - 460800 8N1 - 500000 8N1 - 921600 8N1 - 1000000 8N1 - 1500000 8N1 - 2000000 8N1 - 3000000 8N1 - - - - Baudrate for the TELEM 1 Serial Port - Configure the Baudrate for the TELEM 1 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. - true - - Auto - 50 8N1 - 75 8N1 - 110 8N1 - 134 8N1 - 150 8N1 - 200 8N1 - 300 8N1 - 600 8N1 - 1200 8N1 - 1800 8N1 - 2400 8N1 - 4800 8N1 - 9600 8N1 - 19200 8N1 - 38400 8N1 - 57600 8N1 - 115200 8N1 - 230400 8N1 - 460800 8N1 - 500000 8N1 - 921600 8N1 - 1000000 8N1 - 1500000 8N1 - 2000000 8N1 - 3000000 8N1 - - - - Baudrate for the TELEM 2 Serial Port - Configure the Baudrate for the TELEM 2 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. - true - - Auto - 50 8N1 - 75 8N1 - 110 8N1 - 134 8N1 - 150 8N1 - 200 8N1 - 300 8N1 - 600 8N1 - 1200 8N1 - 1800 8N1 - 2400 8N1 - 4800 8N1 - 9600 8N1 - 19200 8N1 - 38400 8N1 - 57600 8N1 - 115200 8N1 - 230400 8N1 - 460800 8N1 - 500000 8N1 - 921600 8N1 - 1000000 8N1 - 1500000 8N1 - 2000000 8N1 - 3000000 8N1 - - - - Baudrate for the TELEM 3 Serial Port - Configure the Baudrate for the TELEM 3 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. - true - - Auto - 50 8N1 - 75 8N1 - 110 8N1 - 134 8N1 - 150 8N1 - 200 8N1 - 300 8N1 - 600 8N1 - 1200 8N1 - 1800 8N1 - 2400 8N1 - 4800 8N1 - 9600 8N1 - 19200 8N1 - 38400 8N1 - 57600 8N1 - 115200 8N1 - 230400 8N1 - 460800 8N1 - 500000 8N1 - 921600 8N1 - 1000000 8N1 - 1500000 8N1 - 2000000 8N1 - 3000000 8N1 - - - - Baudrate for the TELEM/SERIAL 4 Serial Port - Configure the Baudrate for the TELEM/SERIAL 4 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. - true - - Auto - 50 8N1 - 75 8N1 - 110 8N1 - 134 8N1 - 150 8N1 - 200 8N1 - 300 8N1 - 600 8N1 - 1200 8N1 - 1800 8N1 - 2400 8N1 - 4800 8N1 - 9600 8N1 - 19200 8N1 - 38400 8N1 - 57600 8N1 - 115200 8N1 - 230400 8N1 - 460800 8N1 - 500000 8N1 - 921600 8N1 - 1000000 8N1 - 1500000 8N1 - 2000000 8N1 - 3000000 8N1 - - - - Baudrate for the UART 6 Serial Port - Configure the Baudrate for the UART 6 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. - true - - Auto - 50 8N1 - 75 8N1 - 110 8N1 - 134 8N1 - 150 8N1 - 200 8N1 - 300 8N1 - 600 8N1 - 1200 8N1 - 1800 8N1 - 2400 8N1 - 4800 8N1 - 9600 8N1 - 19200 8N1 - 38400 8N1 - 57600 8N1 - 115200 8N1 - 230400 8N1 - 460800 8N1 - 500000 8N1 - 921600 8N1 - 1000000 8N1 - 1500000 8N1 - 2000000 8N1 - 3000000 8N1 - - - - Baudrate for the Wifi Port Serial Port - Configure the Baudrate for the Wifi Port Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. + + MXS Serial Communication Baud rate + Baudrate for the Serial Port connected to the MXS Transponder + 0 + 10 true - Auto - 50 8N1 - 75 8N1 - 110 8N1 - 134 8N1 - 150 8N1 - 200 8N1 - 300 8N1 - 600 8N1 - 1200 8N1 - 1800 8N1 - 2400 8N1 - 4800 8N1 - 9600 8N1 - 19200 8N1 - 38400 8N1 - 57600 8N1 - 115200 8N1 - 230400 8N1 - 460800 8N1 - 500000 8N1 - 921600 8N1 - 1000000 8N1 - 1500000 8N1 - 2000000 8N1 - 3000000 8N1 + 38400 + 600 + 4800 + 9600 + RESERVED + 57600 + 115200 + 230400 + 19200 + 460800 + 921600 - - Barometer offset in meters - Absolute value superior to 10000 will disable barometer - m - - distance sensor maximun range + distance sensor maximum range 0.0 1000.0 m @@ -11947,7 +9270,7 @@ 0.01 - distance sensor minimun range + distance sensor minimum range 0.0 10.0 m @@ -11955,18 +9278,13 @@ 0.01 - if >= 0 the distance sensor measures will be overrided by this value + if >= 0 the distance sensor measures will be overridden by this value Absolute value superior to 10000 will disable distance sensor m - - Number of GPS satellites used - 0 - 50 - Vehicle inertia about X axis - The intertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. + The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. 0.0 kg m^2 3 @@ -11974,21 +9292,21 @@ Vehicle cross term inertia xy - The intertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. + The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. kg m^2 3 0.005 Vehicle cross term inertia xz - The intertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. + The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. kg m^2 3 0.005 Vehicle inertia about Y axis - The intertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. + The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. 0.0 kg m^2 3 @@ -11996,14 +9314,14 @@ Vehicle cross term inertia yz - The intertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. + The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. kg m^2 3 0.005 Vehicle inertia about Z axis - The intertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. + The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. 0.0 kg m^2 3 @@ -12048,33 +9366,6 @@ 1800000000 deg*1e7 - - North magnetic field at the initial location - This value represents the North magnetic field at the initial location. A magnetic field calculator can be found on the NOAA website Note, the values need to be converted from nano Tesla to Gauss LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. - -1.0 - 1.0 - gauss - 2 - 0.001 - - - East magnetic field at the initial location - This value represents the East magnetic field at the initial location. A magnetic field calculator can be found on the NOAA website Note, the values need to be converted from nano Tesla to Gauss LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. - -1.0 - 1.0 - gauss - 2 - 0.001 - - - Down magnetic field at the initial location - This value represents the Down magnetic field at the initial location. A magnetic field calculator can be found on the NOAA website Note, the values need to be converted from nano Tesla to Gauss LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. - -1.0 - 1.0 - gauss - 2 - 0.001 - Pitch arm length This is the arm length generating the pitching moment This value can be measured with a ruler. This corresponds to half the distance between the front and rear motors. @@ -12091,21 +9382,6 @@ 2 0.05 - - magnetometer X offset in Gauss - Absolute value superior to 10000 will disable magnetometer - gauss - - - magnetometer Y offset in Gauss - Absolute value superior to 10000 will disable magnetometer - gauss - - - magnetometer Z offset in Gauss - Absolute value superior to 10000 will disable magnetometer - gauss - Vehicle mass This value can be measured by weighting the quad on a scale. @@ -12139,24 +9415,51 @@ Vehicle type true - MC - FW + Multicopter + Fixed-Wing + Tailsitter - - - RGB Led brightness limit - Set to 0 to disable, 1 for minimum brightness up to 31 (max) - 0 - 31 + + + simulated barometer pressure offset - - RGB Led brightness limit - Set to 0 to disable, 1 for minimum brightness up to 15 (max) + + simulated barometer temperature offset + celcius + + + simulated GPS number of satellites used 0 - 15 + 50 + + + simulator origin altitude + m + + + simulator origin latitude + deg + + + simulator origin longitude + deg + + + simulated magnetometer X offset + gauss + + + simulated magnetometer Y offset + gauss + + + simulated magnetometer Z offset + gauss + + Automatically configure default values Set to 1 to reset parameters on next system startup (setting defaults). Platform-specific values are used if available. RC* parameters are preserved. @@ -12197,7 +9500,7 @@ Required temperature rise during thermal calibration - A temperature increase greater than this value is required during calibration. Calibration will complete for each sensor when the temperature increase above the starting temeprature exceeds the value set by SYS_CAL_TDEL. If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit. + A temperature increase greater than this value is required during calibration. Calibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL. If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit. 10 celcius @@ -12211,9 +9514,23 @@ Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN. celcius - + + Dataman storage backend + true + + Disabled + default (SD card) + RAM (not persistent) + + + Enable factory calibration mode If enabled, future sensor calibrations will be stored to /fs/mtd_caldata. Note: this is only supported on boards with a separate calibration storage /fs/mtd_caldata. + + Disabled + All sensors + All sensors except mag + Enable failure injection @@ -12229,11 +9546,17 @@ Disable this if the system has no GPS. If disabled, the sensors hub will not process sensor_gps, and GPS will not be available for the rest of the system. true - + Control if the vehicle has a magnetometer - Disable this if the board has no magnetometer, such as the Omnibus F4 SD. If disabled, the preflight checks will not check for the presence of a magnetometer. + Set this to 0 if the board has no magnetometer. If set to 0, the preflight checks will not check for the presence of a magnetometer, otherwise N sensors are required. true + + Number of distance sensors to check being available + The preflight check will fail if fewer than this number of distance sensors with valid data is present. Disable the check with 0. + 0 + 4 + Enable HITL/SIH mode on next boot While enabled the system will boot in Hardware-In-The-Loop (HITL) or Simulation-In-Hardware (SIH) mode and not enable all sensors and checks. When disabled the same vehicle can be flown normally. Set to 'external HITL', if the system should perform as if it were a real vehicle (the only difference to a real system is then only the parameter value, which can be used for log analysis). @@ -12255,26 +9578,22 @@ Q attitude estimator (no position) - - Set restart type - Set by px4io to indicate type of restart - 0 - 2 - - Data survives resets - Data survives in-flight resets only - Data does not survive reset - + + RGB Led brightness limit + Set to 0 to disable, 1 for maximum brightness + % Enable stack checking - + Set usage of IO board - Can be used to use a standard startup script but with a FMU only set-up. Set to 0 to force the FMU only set-up. - 0 - 1 + Can be used to use a configure the use of the IO board. true + + IO PWM disabled (RC only) + IO enabled (RC & PWM) + @@ -12283,42 +9602,6 @@ If true, the FMU will try to connect to Blacksheep telemetry on start up true - - Serial Configuration for FrSky Telemetry - Configure on which serial port to run FrSky Telemetry. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - - - Serial Configuration for HoTT Telemetry - Configure on which serial port to run HoTT Telemetry. - true - - Disabled - UART 6 - TELEM 1 - TELEM 2 - TELEM 3 - TELEM/SERIAL 4 - GPS 1 - GPS 2 - GPS 3 - Radio Controller - Wifi Port - - @@ -12880,42 +10163,274 @@ Gyro rate offset temperature ^2 polynomial coefficient - Z axis - - Gyro rate offset temperature ^3 polynomial coefficient - X axis + + Gyro rate offset temperature ^3 polynomial coefficient - X axis + + + Gyro rate offset temperature ^3 polynomial coefficient - Y axis + + + Gyro rate offset temperature ^3 polynomial coefficient - Z axis + + + Thermal compensation for rate gyro sensors + true + + + ID of Magnetometer that the calibration is for + + + Magnetometer calibration maximum temperature + + + Magnetometer calibration minimum temperature + + + Magnetometer calibration reference temperature + + + Magnetometer offset temperature ^0 polynomial coefficient - X axis + + + Magnetometer offset temperature ^0 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^0 polynomial coefficient - Z axis + + + Magnetometer offset temperature ^1 polynomial coefficient - X axis + + + Magnetometer offset temperature ^1 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^1 polynomial coefficient - Z axis + + + Magnetometer offset temperature ^2 polynomial coefficient - X axis + + + Magnetometer offset temperature ^2 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^2 polynomial coefficient - Z axis + + + Magnetometer offset temperature ^3 polynomial coefficient - X axis + + + Magnetometer offset temperature ^3 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^3 polynomial coefficient - Z axis + + + ID of Magnetometer that the calibration is for + + + Magnetometer calibration maximum temperature + + + Magnetometer calibration minimum temperature + + + Magnetometer calibration reference temperature + + + Magnetometer offset temperature ^0 polynomial coefficient - X axis + + + Magnetometer offset temperature ^0 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^0 polynomial coefficient - Z axis + + + Magnetometer offset temperature ^1 polynomial coefficient - X axis + + + Magnetometer offset temperature ^1 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^1 polynomial coefficient - Z axis + + + Magnetometer offset temperature ^2 polynomial coefficient - X axis + + + Magnetometer offset temperature ^2 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^2 polynomial coefficient - Z axis + + + Magnetometer offset temperature ^3 polynomial coefficient - X axis + + + Magnetometer offset temperature ^3 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^3 polynomial coefficient - Z axis + + + ID of Magnetometer that the calibration is for + + + Magnetometer calibration maximum temperature + + + Magnetometer calibration minimum temperature + + + Magnetometer calibration reference temperature + + + Magnetometer offset temperature ^0 polynomial coefficient - X axis + + + Magnetometer offset temperature ^0 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^0 polynomial coefficient - Z axis + + + Magnetometer offset temperature ^1 polynomial coefficient - X axis + + + Magnetometer offset temperature ^1 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^1 polynomial coefficient - Z axis + + + Magnetometer offset temperature ^2 polynomial coefficient - X axis + + + Magnetometer offset temperature ^2 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^2 polynomial coefficient - Z axis + + + Magnetometer offset temperature ^3 polynomial coefficient - X axis + + + Magnetometer offset temperature ^3 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^3 polynomial coefficient - Z axis + + + ID of Magnetometer that the calibration is for + + + Magnetometer calibration maximum temperature + + + Magnetometer calibration minimum temperature + + + Magnetometer calibration reference temperature + + + Magnetometer offset temperature ^0 polynomial coefficient - X axis + + + Magnetometer offset temperature ^0 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^0 polynomial coefficient - Z axis + + + Magnetometer offset temperature ^1 polynomial coefficient - X axis + + + Magnetometer offset temperature ^1 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^1 polynomial coefficient - Z axis + + + Magnetometer offset temperature ^2 polynomial coefficient - X axis + + + Magnetometer offset temperature ^2 polynomial coefficient - Y axis + + + Magnetometer offset temperature ^2 polynomial coefficient - Z axis + + + Magnetometer offset temperature ^3 polynomial coefficient - X axis - - Gyro rate offset temperature ^3 polynomial coefficient - Y axis + + Magnetometer offset temperature ^3 polynomial coefficient - Y axis - - Gyro rate offset temperature ^3 polynomial coefficient - Z axis + + Magnetometer offset temperature ^3 polynomial coefficient - Z axis - - Thermal compensation for rate gyro sensors + + Thermal compensation for magnetometer sensors true + + + Sagetech External Configuration Mode + Disables auto-configuration mode enabling MXS config through external software. + true + + + Sagetech MXS mode configuration + This parameter defines the operating mode of the MXS + 0 + 3 + false + + Off + On + Standby + Alt + + + + Sagetech MXS Participant Configuration + The MXS communication port to receive Target data from + 0 + 2 + false + + Auto + COM0 + COM1 + + + UAVCAN CAN bus bitrate 20000 1000000 - - UAVCAN Node ID - Read the specs at http://uavcan.org to learn more about Node ID. - 1 - 125 + + Enable MovingBaselineData publication + true - - UAVCAN BATTERY_MONITOR battery monitor selection - This parameter defines that the system will select the battery monitor under the following conditions 0 - default battery monitor 1 - CUAV battery monitor - 0 + + Enable MovingBaselineData subscription 1 true - - default battery monitor - CUAV battery monitor - + + + Enable RTCM subscription + true + + + CAN built-in bus termination + 1 + + + Simulator Gazebo bridge enable + true UAVCAN CAN bus bitrate @@ -12937,10 +10452,6 @@ Sensors and Actuators (ESCs) Automatic Config - - UAVCAN ESC will spin at idle throttle when armed, even if the mixer outputs zero setpoints - true - UAVCAN ANTI_COLLISION light operating mode This parameter defines the minimum condition under which the system will command the ANTI_COLLISION lights on 0 - Always off 1 - When autopilot is armed 2 - When autopilot is prearmed 3 - Always on @@ -13000,6 +10511,21 @@ 125 true + + publish Arming Status stream + Enable UAVCAN Arming Status stream publication uavcan::equipment::safety::ArmingStatus + true + + + publish moving baseline data RTCM stream + Enable UAVCAN RTCM stream publication ardupilot::gnss::MovingBaselineData + true + + + publish RTCM stream + Enable UAVCAN RTCM stream publication uavcan::equipment::gnss::RTCMStream + true + UAVCAN rangefinder maximum range This parameter defines the maximum valid range for a rangefinder connected via UAVCAN. @@ -13010,87 +10536,71 @@ This parameter defines the minimum valid range for a rangefinder connected via UAVCAN. m - - - - UAVCAN/CAN v1 bus bitrate - 20000 - 1000000 - bit/s + + subscription airspeed + Enable UAVCAN airspeed subscriptions. uavcan::equipment::air_data::IndicatedAirspeed uavcan::equipment::air_data::TrueAirspeed uavcan::equipment::air_data::StaticTemperature true - - UAVCAN v1 - 0 - UAVCAN disabled. 1 - Enables UAVCANv1 + + subscription barometer + Enable UAVCAN barometer subscription. uavcan::equipment::air_data::StaticPressure uavcan::equipment::air_data::StaticTemperature true - - actuator_outputs uORB over UAVCAN v1 publication port ID - -1 - 6143 - - - DS-015 battery parameters subscription port ID - -1 - 6143 - - - DS-015 battery status subscription port ID - -1 - 6143 - - - DS-015 battery energy source subscription port ID - -1 - 6143 + + subscription battery + Enable UAVCAN battery subscription. uavcan::equipment::power::BatteryInfo ardupilot::equipment::power::BatteryInfoAux 0 - Disable 1 - Use raw data. Recommended for Smart battery 2 - Filter the data with internal battery library + 0 + 2 + true + + Disable + Raw data + Filter data + - - ESC 0 subscription port ID - -1 - 6143 + + subscription button + Enable UAVCAN button subscription. ardupilot::indication::Button + true - - UAVCAN v1 ESC publication port ID - -1 - 6143 + + subscription differential pressure + Enable UAVCAN differential pressure subscription. uavcan::equipment::air_data::RawAirData + true - - GPS 0 subscription port ID - -1 - 6143 + + subscription flow + Enable UAVCAN optical flow subscription. + true - - GPS 1 subscription port ID - -1 - 6143 + + subscription GPS + Enable UAVCAN GPS subscriptions. uavcan::equipment::gnss::Fix uavcan::equipment::gnss::Fix2 uavcan::equipment::gnss::Auxiliary + true - - UAVCAN v1 GPS publication port ID - -1 - 6143 + + subscription hygrometer + Enable UAVCAN hygrometer subscriptions. dronecan::sensors::hygrometer::Hygrometer + true - - UAVCAN v1 leagcy battery port ID - -1 - 6143 + + subscription ICE + Enable UAVCAN internal combustion engine (ICE) subscription. uavcan::equipment::ice::reciprocating::Status + true - - UAVCAN v1 Servo publication port ID - -1 - 6143 + + subscription IMU + Enable UAVCAN IMU subscription. uavcan::equipment::ahrs::RawIMU + true - - sensor_gps uORB over UAVCAN v1 subscription port ID - -1 - 6143 + + subscription magnetometer + Enable UAVCAN mag subscription. uavcan::equipment::ahrs::MagneticFieldStrength uavcan::equipment::ahrs::MagneticFieldStrength2 + true - - - - UAVCAN v1 Node ID - Read the specs at http://uavcan.org to learn more about Node ID. - 1 - 125 + + subscription range finder + Enable UAVCAN range finder subscription. uavcan::equipment::range_sensor::Measurement true @@ -13185,51 +10695,36 @@ 2 1 - - Backtransition deceleration setpoint to pitch feedforward gain - 0 - 0.2 - rad s^2/m + + Duration motor tilt up in backtransition + Time in seconds it takes to tilt form VT_TILT_FW to VT_TILT_MC. + 0.1 + 10 + s 1 - 0.05 + 0.1 Backtransition deceleration setpoint to pitch I gain 0 0.3 rad s/m - 1 + 2 0.05 Approximate deceleration during back transition - The approximate deceleration during a back transition in m/s/s Used to calculate back transition distance in mission mode. A lower value will make the VTOL transition further from the destination waypoint. For standard vtol and tiltrotors a controller is used to track this value during the transition. + Used to calculate back transition distance in an auto mode. For standard vtol and tiltrotors a controller is used to track this value during the transition. 0.5 10 m/s^2 2 0.1 - - Delay in seconds before applying back transition throttle - Set this to a value greater than 0 to give the motor time to spin down. unit s - 0 - 10 - 2 - 1 - - - Output on airbrakes channel during back transition - Used for airbrakes or with ESCs that have reverse thrust enabled on a seperate channel Airbrakes need to be enables for your selected model/mixer - 0 - 1 - 2 - 0.01 - - - Duration of a back transition - Time in seconds used for a back transition - 0.00 + + Maximum duration of a back transition + Transition is also declared over if the groundspeed drops below MPC_XY_CRUISE. + 0.1 20.00 s 2 @@ -13241,168 +10736,192 @@ 0.0 20.0 s - - - Target throttle value for the transition to hover flight - standard vtol: pusher tailsitter, tiltrotor: main throttle Note for standard vtol: For ESCs and mixers that support reverse thrust on low PWM values set this to a negative value to apply active breaking For ESCs that support thrust reversal with a control channel please set VT_B_REV_OUT and set this to a positive value to apply active breaking - -1 - 1 - 2 - 0.01 - - - Maximum allowed angle the vehicle is allowed to pitch down to generate forward force - When fixed-wing forward actuation is active (see VT_FW_TRHUST_EN). If demanded down pitch exceeds this limmit, the fixed-wing forward actuators are used instead. - 0.0 - 45.0 + 1 + 0.1 - Lock elevons in multicopter mode - If set to 1 the elevons are locked in multicopter mode + Lock control surfaces in hover + If set to 1 the control surfaces are locked at the disarmed value in multicopter mode. - Enable/disable usage of fixed-wing actuators in hover to generate forward force (instead of pitching down) - This technique can be used to avoid the plane having to pitch down in order to move forward. This prevents large, negative lift values being created when facing strong winds. Fixed-wing forward actuators refers to puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL). Only active if demaded down pitch is above VT_DWN_PITCH_MAX, and uses VT_FWD_THRUST_SC to get from demanded down pitch to fixed-wing actuation. + Use fixed-wing actuation in hover to accelerate forward + This feature can be used to avoid the plane having to pitch nose down in order to move forward. Prevents large, negative lift from pitching nose down into wind. Fixed-wing forward actuators refers to puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL). Only active if demanded down pitch is below VT_PITCH_MIN. Use VT_FWD_THRUST_SC to tune it. Only active (if enabled) in Altitude, Position and Auto modes, not in Stabilized. - Disable FW forward actuation in hover. - Enable FW forward actuation in hover in altitude, position and auto modes (except LANDING). - Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT1. - Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT2. - Enable FW forward actuation in hover in altitude, position and auto modes. - Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT1 (except LANDING). - Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT2 (except LANDING). + Disabled + Enabled (except LANDING) + Enabled if distance to ground above MPC_LAND_ALT1 + Enabled if distance to ground above MPC_LAND_ALT2 + Enabled constantly + Enabled if distance to ground above MPC_LAND_ALT1 (except LANDING) + Enabled if distance to ground above MPC_LAND_ALT2 (except LANDING) - Fixed-wing actuator thrust scale for hover forward flight - Scale applied to the demanded down-pitch to get the fixed-wing forward actuation in hover mode. Only active if demaded down pitch is above VT_DWN_PITCH_MAX. Enabled via VT_FWD_THRUST_EN. + Fixed-wing actuation thrust scale for hover forward flight + Scale applied to the demanded down-pitch to get the fixed-wing forward actuation in hover mode. Enabled via VT_FWD_THRUST_EN. 0.0 2.0 - - - Adaptive QuadChute - Maximum negative altitude error for fixed wing flight. If the altitude drops below this value below the altitude setpoint the vehicle will transition back to MC mode and enter failsafe RTL. - 0.0 - 200.0 + 2 + 0.01 Differential thrust in forwards flight - Set to 1 to enable differential thrust in fixed-wing flight. + Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode. The effectiveness of differential thrust around the corresponding axis can be tuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y. 0 - 1 - 0 + 7 + + Yaw + Roll + Pitch + - - Differential thrust scaling factor - This factor specifies how the yaw input gets mapped to differential thrust in forwards flight. + + Pitch differential thrust factor in forward flight + Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN. 0.0 - 1.0 + 2.0 + 2 + 0.1 + + + Roll differential thrust factor in forward flight + Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN. + 0.0 + 2.0 + 2 + 0.1 + + + Yaw differential thrust factor in forward flight + Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN. + 0.0 + 2.0 2 0.1 - QuadChute Altitude - Minimum altitude for fixed wing flight, when in fixed wing the altitude drops below this altitude the vehicle will transition back to MC mode and enter failsafe RTL + Quad-chute altitude + Minimum altitude for fixed-wing flight. When the vehicle is in fixed-wing mode and the altitude drops below this altitude (relative altitude above local origin), it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. 0.0 200.0 + m + 1 + 1 - - The channel number of motors that must be turned off in fixed wing mode + + Quad-chute maximum height + Maximum height above the ground (if available, otherwise above Home if available, otherwise above the local origin) where triggering a quad-chute is possible. At high altitudes there is a big risk to deplete the battery and therefore crash if quad-chuting there. 0 - 12345678 - 0 + m 1 - - Permanent stabilization in fw mode - If set to one this parameter will cause permanent attitude stabilization in fw mode. This parameter has been introduced for pure convenience sake. - - QuadChute Max Pitch - Maximum pitch angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL + Quad-chute max pitch threshold + Absolute pitch threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold. 0 180 + deg - QuadChute Max Roll - Maximum roll angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL + Quad-chute max roll threshold + Absolute roll threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold. 0 180 + deg Duration of a front transition Time in seconds used for a transition - 0.00 + 0.1 20.00 s 2 1 - Target throttle value for the transition to fixed wing flight - standard vtol: pusher tailsitter, tiltrotor: main throttle + Target throttle value for the transition to fixed-wing flight 0.0 1.0 3 0.01 - Airspeed less front transition time (open loop) + Airspeed-less front transition time (open loop) The duration of the front transition when there is no airspeed feedback available. 1.0 30.0 s + 1 + 0.5 - - Idle speed of VTOL when in multicopter mode - 900 - 2000 - us - 0 - 1 + + Minimum pitch angle during hover landing + Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering). During landing it can be beneficial to allow lower minimum pitch angles as it can avoid the wings generating too much lift and preventing the vehicle from sinking at the desired rate. + -10.0 + 45.0 + deg + 1 + 0.1 - - Enable the usage of AUX outputs for hover motors - Set this parameter to true if the vehicle's hover motors are connected to the FMU (AUX) port. Not required for boards that only have a FMU, and no IO. Only applies for standard VTOL and tiltrotor. + + Minimum pitch angle during hover + Any pitch setpoint below this value is translated to a forward force by the fixed-wing forward actuation if VT_FW_TRHUST_EN is set to 1. + -10.0 + 45.0 + deg + 1 + 0.1 - - The channel number of motors which provide lift during hover + + Pusher throttle ramp up slew rate + Defines the slew rate of the puller/pusher throttle during transitions. Zero will deactivate the slew rate limiting and thus produce an instant throttle rise to the transition throttle VT_F_TRANS_THR. 0 - 12345678 - 0 - 1 - - - Pusher throttle ramp up window - Defines the time window during which the pusher throttle will be ramped up linearly to VT_F_TRANS_THR during a transition to fixed wing mode. Zero or negative values will produce an instant throttle rise to VT_F_TRANS_THR. - 20 + 1/s 2 0.01 - - Position of tilt servo in fw mode + + Quad-chute uncommanded descent threshold + Altitude error threshold for quad-chute triggering during fixed-wing flight. The check is only active if altitude is controlled and the vehicle is below the current altitude reference. The altitude error is relative to the highest altitude the vehicle has achieved since it has flown below the current altitude reference. Set to 0 do disable. 0.0 - 1.0 - 3 - 0.01 + 200.0 + m + 1 + 1 - - Position of tilt servo in mc mode + + Quad-chute transition altitude loss threshold + Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight. Active until 5s after completing transition to fixed-wing. Only active if altitude estimate is valid and in altitude-controlled mode. If the current altitude is more than this value below the altitude at the beginning of the transition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold. + 0 + 50 + m + 1 + 1 + + + Spoiler setting while landing (hover) + -1 + 1 + norm + 1 + 0.1 + + + Normalized tilt in FW 0.0 1.0 3 0.01 - - Tilt actuator control value commanded when disarmed and during the first second after arming - This specific tilt during spin-up is necessary for some systems whose motors otherwise don't spin-up freely. + + Normalized tilt in Hover 0.0 1.0 3 0.01 - - Position of tilt servo in transition mode + + Normalized tilt in transition to FW 0.0 1.0 3 @@ -13414,10 +10933,12 @@ 0.0 20.0 s + 1 + 0.1 Duration of front transition phase 2 - Time in seconds it should take for the rotors to rotate forward completely from the point when the plane has picked up enough airspeed and is ready to go into fixed wind mode. + Time in seconds it takes to tilt form VT_TILT_TRANS to VT_TILT_FW. 0.1 5.0 s @@ -13427,7 +10948,7 @@ Front transition timeout Time in seconds after which transition will be cancelled. Disabled if set to 0. - 0.00 + 0.1 30.00 s 2 @@ -13437,7 +10958,6 @@ VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2) 0 2 - 0 true Tailsitter @@ -13455,73 +10975,18 @@ 0.01 - - - Inertia matrix, XX component - kg m^2 - 5 - 0.00001 - - - Inertia matrix, XY component - kg m^2 - 5 - 0.00001 - - - Inertia matrix, XZ component - kg m^2 - 5 - 0.00001 - - - Inertia matrix, YY component - kg m^2 - 5 - 0.00001 - - - Inertia matrix, YZ component - kg m^2 - 5 - 0.00001 - - - Inertia matrix, ZZ component - kg m^2 - 5 - 0.00001 - - - Mass - kg - 5 - 0.00001 + + + VTOL Takeoff relative loiter altitude + Altitude relative to home at which vehicle will loiter after front transition. + 20 + 300 + m + 1 + 1 - - EXFW_HDNG_P - - - EXFW_PITCH_P - - - EXFW_ROLL_P - - - Enable user assisted descent speed for autonomous land routine - When enabled, descent speed will be: stick full up - 0 stick centered - MPC_LAND_SPEED stick full down - 2 * MPC_LAND_SPEED - 0 - 1 - - Fixed descent speed of MPC_LAND_SPEED - User assisted descent speed - - - - RV_YAW_P - Skip the controller From 9ca8cc57e4f8ff1e1b83bc4f94d271797c237dc5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 26 Sep 2023 11:51:36 +0200 Subject: [PATCH 056/118] libevents: update submodule --- libs/libevents/libevents | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libs/libevents/libevents b/libs/libevents/libevents index 82dabdb914d..59f7f5c0ec2 160000 --- a/libs/libevents/libevents +++ b/libs/libevents/libevents @@ -1 +1 @@ -Subproject commit 82dabdb914d7bd640c281900e2852d0afc074b68 +Subproject commit 59f7f5c0ec2e76fadbc1dc40cc0705d614472edc From dfcf25a5762a25c26b613c1a472e0390009a285c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 26 Sep 2023 11:56:12 +0200 Subject: [PATCH 057/118] Vehicle: fix html escaping for events & rich text rendering Also removes unused getLatestError() --- src/Vehicle/EventHandler.cc | 3 +++ src/Vehicle/Vehicle.cc | 20 +++++--------------- src/Vehicle/Vehicle.h | 6 +----- src/uas/UASMessageHandler.cc | 16 +++++++++------- src/uas/UASMessageHandler.h | 12 ++++-------- src/ui/MainRootWindow.qml | 1 + 6 files changed, 23 insertions(+), 35 deletions(-) diff --git a/src/Vehicle/EventHandler.cc b/src/Vehicle/EventHandler.cc index 7285f4afecc..0c8f57867ea 100644 --- a/src/Vehicle/EventHandler.cc +++ b/src/Vehicle/EventHandler.cc @@ -45,6 +45,9 @@ EventHandler::EventHandler(QObject* parent, const QString& profile, handle_event _parser.formatters().param = [](const std::string& content) { return ""+content+""; }; + _parser.formatters().escape = [](const std::string& str) { + return QString::fromStdString(str).toHtmlEscaped().toStdString(); }; + events::ReceiveProtocol::Callbacks callbacks{error_cb, _sendRequestCB, std::bind(&EventHandler::gotEvent, this, std::placeholders::_1), timeout_cb}; _protocol = new events::ReceiveProtocol(callbacks, ourSystemId, ourComponentId, systemId, componentId); diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index ea4d8589d0f..f4c91fecbe7 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -925,7 +925,7 @@ void Vehicle::_chunkedStatusTextCompleted(uint8_t compId) qgcApp()->toolbox()->audioOutput()->say(messageText); } } - emit textMessageReceived(id(), compId, severity, messageText); + emit textMessageReceived(id(), compId, severity, messageText.toHtmlEscaped(), ""); } void Vehicle::_handleStatusText(mavlink_message_t& message) @@ -1605,24 +1605,19 @@ void Vehicle::_handleEvent(uint8_t comp_id, std::unique_ptr"; + message += "- " + messageCheck + "\n"; } } } - if (message.size() > 0) { - // TODO: handle this properly in the UI (e.g. with an expand button to display the description, clickable URL's + params)... - QString msg = QString::fromStdString(message); - if (description.size() > 0) { - msg += "
" + QString::fromStdString(description).replace("\n", "
") + "
"; - } - emit textMessageReceived(id(), comp_id, severity, msg); + if (!message.empty()) { + emit textMessageReceived(id(), comp_id, severity, QString::fromStdString(message), QString::fromStdString(description)); } } } @@ -2030,11 +2025,6 @@ void Vehicle::_handleTextMessage(int newCount) _messageCount = newCount; emit messageCountChanged(); } - QString errMsg = pMh->getLatestError(); - if(errMsg != _latestError) { - _latestError = errMsg; - emit latestErrorChanged(); - } } void Vehicle::resetAllMessages() diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index b8f9b7ca978..9fc87f00789 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -177,7 +177,6 @@ class Vehicle : public FactGroup Q_PROPERTY(int newMessageCount READ newMessageCount NOTIFY newMessageCountChanged) Q_PROPERTY(int messageCount READ messageCount NOTIFY messageCountChanged) Q_PROPERTY(QString formattedMessages READ formattedMessages NOTIFY formattedMessagesChanged) - Q_PROPERTY(QString latestError READ latestError NOTIFY latestErrorChanged) Q_PROPERTY(bool joystickEnabled READ joystickEnabled WRITE setJoystickEnabled NOTIFY joystickEnabledChanged) Q_PROPERTY(int flowImageIndex READ flowImageIndex NOTIFY flowImageIndexChanged) Q_PROPERTY(int rcRSSI READ rcRSSI NOTIFY rcRSSIChanged) @@ -595,7 +594,6 @@ class Vehicle : public FactGroup int newMessageCount () const{ return _currentMessageCount; } int messageCount () const{ return _messageCount; } QString formattedMessages (); - QString latestError () { return _latestError; } float latitude () { return static_cast(_coordinate.latitude()); } float longitude () { return static_cast(_coordinate.longitude()); } bool mavPresent () { return _mav != nullptr; } @@ -919,7 +917,7 @@ public slots: void capabilityBitsChanged (uint64_t capabilityBits); void toolIndicatorsChanged (); void modeIndicatorsChanged (); - void textMessageReceived (int uasid, int componentid, int severity, QString text); + void textMessageReceived (int uasid, int componentid, int severity, QString text, QString description); void calibrationEventReceived (int uasid, int componentid, int severity, QSharedPointer event); void checkListStateChanged (); void messagesReceivedChanged (); @@ -930,7 +928,6 @@ public slots: void messageCountChanged (); void formattedMessagesChanged (); void newFormattedMessage (QString formattedMessage); - void latestErrorChanged (); void longitudeChanged (); void currentConfigChanged (); void flowImageIndexChanged (); @@ -1129,7 +1126,6 @@ private slots: int _currentWarningCount = 0; int _currentNormalCount = 0; MessageType_t _currentMessageType = MessageNone; - QString _latestError; int _updateCount = 0; int _rcRSSI = 255; double _rcRSSIstore = 255; diff --git a/src/uas/UASMessageHandler.cc b/src/uas/UASMessageHandler.cc index 9a4a2641afd..13e9539b508 100644 --- a/src/uas/UASMessageHandler.cc +++ b/src/uas/UASMessageHandler.cc @@ -103,13 +103,19 @@ void UASMessageHandler::_activeVehicleChanged(Vehicle* vehicle) } } -void UASMessageHandler::handleTextMessage(int, int compId, int severity, QString text) +void UASMessageHandler::handleTextMessage(int, int compId, int severity, QString text, QString description) { // Hack to prevent calibration messages from cluttering things up if (_activeVehicle->px4Firmware() && text.startsWith(QStringLiteral("[cal] "))) { return; } + text = text.replace("\n", "
"); + // TODO: handle text + description separately in the UI + if (!description.isEmpty()) { + text += "
" + description.replace("\n", "
") + "
"; + } + // Color the output depending on the message severity. We have 3 distinct cases: // 1: If we have an ERROR or worse, make it bigger, bolder, and highlight it red. // 2: If we have a warning or notice, just make it bold and color it orange. @@ -187,11 +193,7 @@ void UASMessageHandler::handleTextMessage(int, int compId, int severity, QString if (_multiComp) { compString = QString(" COMP:%1").arg(compId); } - message->_setFormatedText(QString("[%2%3]%4 %5
").arg(style).arg(dateString).arg(compString).arg(severityText).arg(text.toHtmlEscaped())); - - if (message->severityIsError()) { - _latestError = severityText + " " + text; - } + message->_setFormatedText(QString("[%2%3]%4 %5
").arg(style).arg(dateString).arg(compString).arg(severityText).arg(text)); _mutex.unlock(); @@ -202,7 +204,7 @@ void UASMessageHandler::handleTextMessage(int, int compId, int severity, QString emit textMessageCountChanged(count); if (_showErrorsInToolbar && message->severityIsError()) { - _app->showCriticalVehicleMessage(message->getText().toHtmlEscaped()); + _app->showCriticalVehicleMessage(message->getText()); } } diff --git a/src/uas/UASMessageHandler.h b/src/uas/UASMessageHandler.h index 402eccd4590..6cb329d4bdf 100644 --- a/src/uas/UASMessageHandler.h +++ b/src/uas/UASMessageHandler.h @@ -37,7 +37,7 @@ class UASMessage */ int getSeverity() const { return _severity; } /** - * @brief Get message text (e.g. "[pm] sending list") + * @brief Get (html escaped) message text (e.g. "[pm] sending list") */ QString getText() { return _text; } /** @@ -98,10 +98,6 @@ class UASMessageHandler : public QGCTool * @brief Get normal message count (Resets count once read) */ int getNormalCount(); - /** - * @brief Get latest error message - */ - QString getLatestError() { return _latestError; } /// Begin to show message which are errors in the toolbar void showErrorsInToolbar(void) { _showErrorsInToolbar = true; } @@ -115,9 +111,10 @@ public slots: * @param uasid UAS Id * @param componentid Component Id * @param severity Message severity - * @param text Message Text + * @param text Message Text (html escaped) + * @param description Optional detailed description (html escaped) */ - void handleTextMessage(int uasid, int componentid, int severity, QString text); + void handleTextMessage(int uasid, int componentid, int severity, QString text, QString description); signals: /** @@ -144,7 +141,6 @@ private slots: int _errorCountTotal; int _warningCount; int _normalCount; - QString _latestError; bool _showErrorsInToolbar; MultiVehicleManager* _multiVehicleManager; }; diff --git a/src/ui/MainRootWindow.qml b/src/ui/MainRootWindow.qml index ac7a16f1069..93274b3fcc4 100644 --- a/src/ui/MainRootWindow.qml +++ b/src/ui/MainRootWindow.qml @@ -617,6 +617,7 @@ ApplicationWindow { anchors.centerIn: parent wrapMode: Text.WordWrap color: qgcPal.alertText + textFormat: TextEdit.RichText } MouseArea { From 5fed5222dfb04f056bf7315c1ba87b6f09e611c7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 26 Sep 2023 11:58:33 +0200 Subject: [PATCH 058/118] MessageIndicator: handle url & parameter links --- src/ui/toolbar/MessageIndicator.qml | 26 ++++++++++++++++++++++++++ 1 file changed, 26 insertions(+) diff --git a/src/ui/toolbar/MessageIndicator.qml b/src/ui/toolbar/MessageIndicator.qml index 397c81a55bf..6bb0e56f1fd 100644 --- a/src/ui/toolbar/MessageIndicator.qml +++ b/src/ui/toolbar/MessageIndicator.qml @@ -14,6 +14,7 @@ import QtQuick.Layouts 1.2 import QGroundControl 1.0 import QGroundControl.Controls 1.0 +import QGroundControl.FactSystem 1.0 import QGroundControl.MultiVehicleManager 1.0 import QGroundControl.ScreenTools 1.0 import QGroundControl.Palette 1.0 @@ -142,6 +143,10 @@ Item { } } + FactPanelController { + id: controller + } + QGCFlickable { id: messageFlick anchors.margins: ScreenTools.defaultFontPixelHeight @@ -158,6 +163,27 @@ Item { color: qgcPal.text selectionColor: qgcPal.text selectedTextColor: qgcPal.window + property var fact: null + onLinkActivated: { + if (link.startsWith('param://')) { + var paramName = link.substr(8); + fact = controller.getParameterFact(-1, paramName, true) + if (fact != null) { + paramEditorDialogComponent.createObject(mainWindow).open() + } + } else { + Qt.openUrlExternally(link); + } + } + } + Component { + id: paramEditorDialogComponent + + ParameterEditorDialog { + title: qsTr("Edit Parameter") + fact: messageText.fact + destroyOnClose: true + } } } } From 2ed383cec91f1b13d44761cb5cb850409aaf91a5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 26 Sep 2023 13:53:58 +0200 Subject: [PATCH 059/118] ci: limit git fetch depth to 1 Fetching failed because the remote changed in a submodule: fatal: remote error: upload-pack: not our ref 391786c6c3abdd3eeb993a3154f1f2a4cfe137a0 Errors during submodule fetch: libs/cpp/parse/nlohmann_json --- .github/workflows/android_release.yml | 2 +- .github/workflows/linux_release.yml | 2 +- .github/workflows/macos_release.yml | 2 +- .github/workflows/windows_release.yml | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/android_release.yml b/.github/workflows/android_release.yml index 454839bf147..c007fc63b38 100644 --- a/.github/workflows/android_release.yml +++ b/.github/workflows/android_release.yml @@ -44,7 +44,7 @@ jobs: - name: Get all tags for correct version determination working-directory: ${{ github.workspace }} run: | - git fetch --all --tags -f + git fetch --all --tags -f --depth 1 - name: Install Qt uses: jurplel/install-qt-action@v3 diff --git a/.github/workflows/linux_release.yml b/.github/workflows/linux_release.yml index c4b48956ccf..19fe178c2c3 100644 --- a/.github/workflows/linux_release.yml +++ b/.github/workflows/linux_release.yml @@ -34,7 +34,7 @@ jobs: - name: Get all tags for correct version determination working-directory: ${{ github.workspace }} run: | - git fetch --all --tags -f + git fetch --all --tags -f --depth 1 - name: Install Qt uses: jurplel/install-qt-action@v3 diff --git a/.github/workflows/macos_release.yml b/.github/workflows/macos_release.yml index b2da1b59c7c..45761482dac 100644 --- a/.github/workflows/macos_release.yml +++ b/.github/workflows/macos_release.yml @@ -34,7 +34,7 @@ jobs: - name: Get all tags for correct version determination working-directory: ${{ github.workspace }} run: | - git fetch --all --tags -f + git fetch --all --tags -f --depth 1 - name: Install Qt uses: jurplel/install-qt-action@v3 diff --git a/.github/workflows/windows_release.yml b/.github/workflows/windows_release.yml index 301b986cb72..8c4352d1b3f 100644 --- a/.github/workflows/windows_release.yml +++ b/.github/workflows/windows_release.yml @@ -34,7 +34,7 @@ jobs: - name: Get all tags for correct version determination working-directory: ${{ github.workspace }} run: | - git fetch --all --tags -f + git fetch --all --tags -f --depth 1 - name: Install Qt uses: jurplel/install-qt-action@v3 From 6e26121edf5360ecf20e898d0aa791974592dd77 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Wed, 27 Sep 2023 16:34:38 +0200 Subject: [PATCH 060/118] VideoSettings: Flag Herelink streams as configured: otherwise videoManager won't restart the receiver and video won't work properly when configured for Herelink --- src/Settings/VideoSettings.cc | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/Settings/VideoSettings.cc b/src/Settings/VideoSettings.cc index 8ade41d1f35..89e8a6b448e 100644 --- a/src/Settings/VideoSettings.cc +++ b/src/Settings/VideoSettings.cc @@ -225,6 +225,16 @@ bool VideoSettings::streamConfigured(void) qCDebug(VideoManagerLog) << "Testing configuration for MPEG-TS Stream:" << udpPort()->rawValue().toInt(); return udpPort()->rawValue().toInt() != 0; } + //-- If Herelink Air unit, good to go + if(vSource == videoSourceHerelinkAirUnit) { + qCDebug(VideoManagerLog) << "Stream configured for Herelink Air Unit"; + return true; + } + //-- If Herelink Hotspot, good to go + if(vSource == videoSourceHerelinkHotspot) { + qCDebug(VideoManagerLog) << "Stream configured for Herelink Hotspot"; + return true; + } return false; } From ee007746eff76062f30aa958d02fc695bb9d707f Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Fri, 6 Oct 2023 15:36:41 +0000 Subject: [PATCH 061/118] Update PX4 Firmware metadata Fri Oct 6 15:36:41 UTC 2023 --- .../PX4/PX4ParameterFactMetaData.xml | 75 ++++++++----------- 1 file changed, 32 insertions(+), 43 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index bf9c8911402..2241347e77f 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -357,14 +357,14 @@
- Airspeed Selector: Gate size for sideslip angle fusion + Gate size for sideslip angle fusion Sets the number of standard deviations used by the innovation consistency test. 1 5 SD - Airspeed Selector: Wind estimator sideslip measurement noise + Wind estimator sideslip measurement noise Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector. 0 1 @@ -373,7 +373,7 @@ Enable checks on airspeed sensors - Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0. Note that the data missing check is enabled if any of the options is set. + Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0. 0 15 @@ -465,7 +465,7 @@ - Airspeed Selector: Wind estimator true airspeed scale process noise spectral density + Wind estimator true airspeed scale process noise spectral density Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second. 0 0.1 @@ -473,14 +473,14 @@ 5 - Airspeed Selector: Gate size for true airspeed fusion + Gate size for true airspeed fusion Sets the number of standard deviations used by the innovation consistency test. 1 5 SD - Airspeed Selector: Wind estimator true airspeed measurement noise + Wind estimator true airspeed measurement noise True airspeed measurement noise of the internal wind estimator(s) of the airspeed selector. 0 4 @@ -489,14 +489,14 @@ Horizontal wind uncertainty threshold for synthetic airspeed - The synthetic airspeed estimate (from groundspeed and heading) will be declared valid as soon and as long the horizontal wind uncertainty drops below this value. + The synthetic airspeed estimate (from groundspeed and heading) will be declared valid as soon and as long the horizontal wind uncertainty is below this value. 0.001 5 m/s 3 - Airspeed Selector: Wind estimator wind process noise noise spectral density + Wind estimator wind process noise spectral density Wind process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. 0 1 @@ -1640,7 +1640,7 @@ Airspeed fusion threshold - A value of zero will deactivate airspeed fusion. Any other positive value will determine the minimum airspeed which will still be fused. Set to about 90% of the vehicles stall speed. Both airspeed fusion and sideslip fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_FUSE_BETA to activate sideslip fusion. Note: side slip fusion is currently not supported for tailsitters. + Airspeed data is fused for wind estimation if above this threshold. Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies to fixed-wing vehicles (or VTOLs in fixed-wing mode). 0.0 m/s 1 @@ -1838,8 +1838,8 @@ 1 - Boolean determining if synthetic sideslip measurements should fused - A value of 1 indicates that fusion is active Both sideslip fusion and airspeed fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_ARSP_THR to activate airspeed fusion. + Enable synthetic sideslip fusion + For reliable wind estimation both sideslip and airspeed fusion (see EKF2_ARSP_THR) should be enabled. Only applies to fixed-wing vehicles (or VTOLs in fixed-wing mode). Note: side slip fusion is currently not supported for tailsitters. 1-sigma IMU gyro switch-on bias @@ -2526,7 +2526,7 @@ Maximum manual pitch angle - Maximum manual pitch angle setpoint (positive & negative) in manual attitude-only stabilized mode + Applies to both directions in all manual modes with attitude stabilization but without altitude control 0.0 90.0 deg @@ -2535,7 +2535,7 @@ Maximum manual roll angle - Maximum manual roll angle setpoint (positive & negative) in manual attitude-only stabilized mode + Applies to both directions in all manual modes with attitude stabilization 0.0 90.0 deg @@ -2544,7 +2544,7 @@ Maximum manually added yaw rate - This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode. The controller already generates a yaw rate setpoint to coordinate a turn, and this value is added to it. This is an absolute value, which is applied symmetrically to the negative and positive side. + This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode. It is added to the yaw rate setpoint generated by the controller for turn coordination. 0 deg/s 1 @@ -2577,7 +2577,7 @@ Attitude pitch time constant - This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed. + This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Smaller systems may require smaller values. 0.2 1.0 s @@ -2594,7 +2594,7 @@ Attitude Roll Time Constant - This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed. + This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Smaller systems may require smaller values. 0.2 1.0 s @@ -2619,7 +2619,6 @@ Wheel steering rate feed forward - Direct feed forward from rate setpoint to control surface output 0.0 10 %/rad/s @@ -2637,7 +2636,6 @@ Wheel steering rate integrator limit - The portion of the integrator part in the control surface deflection is limited to this value 0.0 1.0 2 @@ -2704,7 +2702,7 @@ Early landing configuration deployment - When disabled, the landing configuration (flaps, landing airspeed, etc.) is only activated on the final approach to landing. When enabled, it is already activated when entering the final loiter-down (loiter-to-alt) waypoint before the landing approach. This shifts the (often large) altitude and airspeed errors caused by the configuration change away from the ground such that these are not so critical. It also gives the controller enough time to adapt to the new configuration such that the landing approach starts with a cleaner initial state. + When disabled, the landing configuration (flaps, landing airspeed, etc.) is only activated on the final approach to landing. When enabled, it is already activated when entering the final loiter-down (loiter-to-alt) waypoint before the landing approach. Landing flare altitude (relative to landing altitude) @@ -2835,8 +2833,8 @@ 0.5 - FW Launch detection - Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles. Only available for fixed-wing vehicles. Not compatible with runway takeoff. + Fixed-wing launch detection + Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles. Not compatible with runway takeoff. Motor delay @@ -2958,8 +2956,7 @@ - Acro body x max rate - This is the rate the controller is trying to achieve if the user applies full roll stick input in acro mode. + Acro body roll max rate setpoint 10 720 deg @@ -3107,7 +3104,6 @@ Pitch rate integrator gain - This gain defines how much control response will result out of a steady state error. It trims any constant error. 0.0 10 %/rad @@ -3116,7 +3112,6 @@ Pitch rate integrator limit - The portion of the integrator part in the control surface deflection is limited to this value 0.0 1.0 2 @@ -3137,9 +3132,8 @@ 1 0.01 - - Roll rate derivative Gain - Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + + Roll rate derivative gain 0.0 10 %/rad/s @@ -3148,7 +3142,7 @@ Roll rate feed forward - Direct feed forward from rate setpoint to control surface output. Use this to obtain a tigher response of the controller without introducing noise amplification. + Direct feed forward from rate setpoint to control surface output. 0.0 10.0 %/rad/s @@ -3156,8 +3150,7 @@ 0.05 - Roll rate integrator Gain - This gain defines how much control response will result out of a steady state error. It trims any constant error. + Roll rate integrator gain 0.0 10 %/rad @@ -3165,15 +3158,14 @@ 0.01 - Roll integrator anti-windup - The portion of the integrator part in the control surface deflection is limited to this value. + Roll integrator limit 0.0 1.0 2 0.05 - Roll rate proportional Gain + Roll rate proportional gain 0.0 10 %/rad/s @@ -3191,7 +3183,6 @@ Yaw rate derivative gain - Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. 0.0 10 %/rad/s @@ -3209,7 +3200,6 @@ Yaw rate integrator gain - This gain defines how much control response will result out of a steady state error. It trims any constant error. 0.0 10 %/rad @@ -3218,7 +3208,6 @@ Yaw rate integrator limit - The portion of the integrator part in the control surface deflection is limited to this value 0.0 1.0 2 @@ -3244,7 +3233,7 @@ Minimum Airspeed (CAS) - The minimal airspeed (calibrated airspeed) the user is able to command. Further, if the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. Has to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL), with some margin between the stall speed and minimum airspeed. This value corresponds to the desired minimum speed with the default load factor (level flight, default weight), and is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE). + The minimal airspeed (calibrated airspeed) the user is able to command. Further, if the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. Should be set (with some margin) above the vehicle stall speed. This value corresponds to the desired minimum speed with the default load factor (level flight, default weight), and is automatically adapated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE). 0.5 m/s 1 @@ -3320,7 +3309,7 @@ Throttle limit max - This is the maximum throttle % that can be used by the controller. For overpowered aircraft, this should be reduced to a value that provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX. + Maximum throttle limit in altitude controlled modes. Should be set accordingly to achieve FW_T_CLMB_MAX. 0.0 1.0 norm @@ -3329,7 +3318,7 @@ Throttle limit min - This is the minimum throttle % that can be used by the controller. For electric aircraft this will normally be set to zero, but can be set to a small non-zero value if a folding prop is fitted to prevent the prop from folding and unfolding repeatedly in-flight or to provide some aerodynamic drag from a turning prop to improve the descent rate. For aircraft with internal combustion engine this parameter should be set for desired idle rpm. + Minimum throttle limit in altitude controlled modes. Usually set to 0 but can be increased to prevent the motor from stopping when descending, which can increase achievable descent rates. For aircraft with internal combustion engine this parameter should be set for desired idle rpm. 0.0 1.0 norm @@ -3526,7 +3515,7 @@ Wind-based airspeed scaling factor - Multiplying this factor with the current absolute wind estimate gives the airspeed offset added to the minimum airspeed setpoint limit. This helps to make the system more robust against disturbances (turbulence) in high wind. Only applies to AUTO flight mode. airspeed_min_adjusted = FW_AIRSPD_MIN + FW_WIND_ARSP_SC * wind.length() + Multiplying this factor with the current absolute wind estimate gives the airspeed offset added to the minimum airspeed setpoint limit. This helps to make the system more robust against disturbances (turbulence) in high wind. Only applies to AUTO flight mode. 0 2 0.01 @@ -10856,7 +10845,7 @@ Minimum pitch angle during hover landing - Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering). During landing it can be beneficial to allow lower minimum pitch angles as it can avoid the wings generating too much lift and preventing the vehicle from sinking at the desired rate. + Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering). During landing it can be beneficial to reduce the pitch angle to reduce the generated lift in head wind. -10.0 45.0 deg @@ -10891,7 +10880,7 @@ Quad-chute transition altitude loss threshold - Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight. Active until 5s after completing transition to fixed-wing. Only active if altitude estimate is valid and in altitude-controlled mode. If the current altitude is more than this value below the altitude at the beginning of the transition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold. + Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight in altitude-controlled flight modes. Active until 5s after completing transition to fixed-wing. If the current altitude is more than this value below the altitude at the beginning of the transition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold. 0 50 m From 2e9577189f12d6acb89b5d66a9286192f5c918af Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Mon, 9 Oct 2023 06:48:52 +0000 Subject: [PATCH 062/118] Update PX4 Firmware metadata Mon Oct 9 06:48:52 UTC 2023 --- .../PX4/PX4ParameterFactMetaData.xml | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 2241347e77f..bdcaa25597b 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -908,6 +908,15 @@ 1 0.1 + + Minimum battery level for arming + Additional battery level check that only allows arming if the state of charge of the emptiest connected battery is above this value. A value of 0 disables the check. + 0 + 0.9 + norm + 2 + 0.01 + Enable checks on ESCs that report telemetry If this parameter is set, the system will check ESC's online status and failures. This param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry. @@ -1042,7 +1051,7 @@ Delay between failsafe condition triggered and failsafe reaction - Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode for the user to realize. During that time the user cannot take over control via the stick override feature see COM_RC_OVERRIDE. Afterwards the configured failsafe action is triggered and the user may use stick override. A zero value disables the delay and the user cannot take over via stick movements (switching modes is still allowed). + Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode for the user to realize. During that time the user cannot take over control via the stick override feature (see COM_RC_OVERRIDE). Afterwards the configured failsafe action is triggered and the user may use stick override. A zero value disables the delay and the user cannot take over via stick movements (switching modes is still allowed). 0.0 25.0 s @@ -1376,8 +1385,8 @@ - RC loss time threshold - After this amount of seconds without RC connection it's considered lost and not used anymore + Manual control loss timeout + The time in seconds without a new setpoint from RC or Joystick, after which the connection is considered lost. This must be kept short as the vehicle will use the last supplied setpoint until the timeout triggers. 0 35 s From 09dca9a1bc91001d7eb5946da320bb0baf8be546 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Mon, 21 Nov 2022 21:50:20 +0100 Subject: [PATCH 063/118] Vehicle: remove unused extraJoystickFlightModes --- src/FirmwarePlugin/FirmwarePlugin.h | 4 ---- src/Joystick/Joystick.cc | 6 +----- src/Vehicle/Vehicle.cc | 5 ----- src/Vehicle/Vehicle.h | 2 -- 4 files changed, 1 insertion(+), 16 deletions(-) diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index a3956747263..f4f05a0139d 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -88,10 +88,6 @@ class FirmwarePlugin : public QObject /// list available from the firmware. Call will be made again if advanced mode changes. virtual QStringList flightModes(Vehicle* /*vehicle*/) { return QStringList(); } - /// Returns the list of additional flight modes to add to the list for joystick button actions. - /// Call will be made again if advanced mode changes. - virtual QStringList extraJoystickFlightModes(Vehicle* /*vehicle*/) { return QStringList(); } - /// Returns the name for this flight mode. Flight mode names must be human readable as well as audio speakable. /// @param base_mode Base mode from mavlink HEARTBEAT message /// @param custom_mode Custom mode from mavlink HEARTBEAT message diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index ddc3ed3cfb5..e138739eeca 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -1011,7 +1011,7 @@ void Joystick::_executeButtonAction(const QString& action, bool buttonDown) if (buttonDown) emit setVtolInFwdFlight(true); } else if (action == _buttonActionVTOLMultiRotor) { if (buttonDown) emit setVtolInFwdFlight(false); - } else if (_activeVehicle->flightModes().contains(action) || _activeVehicle->extraJoystickFlightModes().contains(action)) { + } else if (_activeVehicle->flightModes().contains(action)) { if (buttonDown) emit setFlightMode(action); } else if(action == _buttonActionContinuousZoomIn || action == _buttonActionContinuousZoomOut) { if (buttonDown) { @@ -1128,10 +1128,6 @@ void Joystick::_buildActionList(Vehicle* activeVehicle) foreach(auto mode, list) { _assignableButtonActions.append(new AssignableButtonAction(this, mode)); } - list = activeVehicle->extraJoystickFlightModes(); - foreach(auto mode, list) { - _assignableButtonActions.append(new AssignableButtonAction(this, mode)); - } } _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionVTOLFixedWing)); _assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionVTOLMultiRotor)); diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index f4c91fecbe7..0faa32593ca 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -2185,11 +2185,6 @@ QStringList Vehicle::flightModes() return _firmwarePlugin->flightModes(this); } -QStringList Vehicle::extraJoystickFlightModes() -{ - return _firmwarePlugin->extraJoystickFlightModes(this); -} - QString Vehicle::flightMode() const { return _firmwarePlugin->flightMode(_base_mode, _custom_mode); diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 9fc87f00789..18acaecb4fc 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -164,7 +164,6 @@ class Vehicle : public FactGroup Q_PROPERTY(bool autoDisarm READ autoDisarm NOTIFY autoDisarmChanged) Q_PROPERTY(bool flightModeSetAvailable READ flightModeSetAvailable CONSTANT) Q_PROPERTY(QStringList flightModes READ flightModes NOTIFY flightModesChanged) - Q_PROPERTY(QStringList extraJoystickFlightModes READ extraJoystickFlightModes NOTIFY flightModesChanged) Q_PROPERTY(QString flightMode READ flightMode WRITE setFlightMode NOTIFY flightModeChanged) Q_PROPERTY(TrajectoryPoints* trajectoryPoints MEMBER _trajectoryPoints CONSTANT) Q_PROPERTY(QmlObjectListModel* cameraTriggerPoints READ cameraTriggerPoints CONSTANT) @@ -521,7 +520,6 @@ class Vehicle : public FactGroup bool flightModeSetAvailable (); QStringList flightModes (); - QStringList extraJoystickFlightModes (); QString flightMode () const; void setFlightMode (const QString& flightMode); From c3d569d6aef228d7fd4f1100692fd8d5bb078138 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Mon, 21 Nov 2022 21:51:37 +0100 Subject: [PATCH 064/118] Vehicle: implement MAVLink standard modes --- qgroundcontrol.pro | 2 + src/Vehicle/CMakeLists.txt | 2 + src/Vehicle/InitialConnectStateMachine.cc | 20 +++ src/Vehicle/InitialConnectStateMachine.h | 2 + src/Vehicle/StandardModes.cc | 179 ++++++++++++++++++++++ src/Vehicle/StandardModes.h | 69 +++++++++ src/Vehicle/Vehicle.cc | 32 +++- src/Vehicle/Vehicle.h | 3 + 8 files changed, 307 insertions(+), 2 deletions(-) create mode 100644 src/Vehicle/StandardModes.cc create mode 100644 src/Vehicle/StandardModes.h diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 73ea5522420..4f9ca79142e 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -724,6 +724,7 @@ HEADERS += \ src/Vehicle/MultiVehicleManager.h \ src/Vehicle/RemoteIDManager.h \ src/Vehicle/StateMachine.h \ + src/Vehicle/StandardModes.h \ src/Vehicle/SysStatusSensorInfo.h \ src/Vehicle/TerrainFactGroup.h \ src/Vehicle/TerrainProtocolHandler.h \ @@ -979,6 +980,7 @@ SOURCES += \ src/Vehicle/MultiVehicleManager.cc \ src/Vehicle/RemoteIDManager.cc \ src/Vehicle/StateMachine.cc \ + src/Vehicle/StandardModes.cc \ src/Vehicle/SysStatusSensorInfo.cc \ src/Vehicle/TerrainFactGroup.cc \ src/Vehicle/TerrainProtocolHandler.cc \ diff --git a/src/Vehicle/CMakeLists.txt b/src/Vehicle/CMakeLists.txt index b58cb585c4a..eaabd67edff 100644 --- a/src/Vehicle/CMakeLists.txt +++ b/src/Vehicle/CMakeLists.txt @@ -56,6 +56,8 @@ add_library(Vehicle MultiVehicleManager.h StateMachine.cc StateMachine.h + StandardModes.cc + StandardModes.h SysStatusSensorInfo.cc SysStatusSensorInfo.h TerrainFactGroup.cc diff --git a/src/Vehicle/InitialConnectStateMachine.cc b/src/Vehicle/InitialConnectStateMachine.cc index 13ec32eb83e..1d178c7cafd 100644 --- a/src/Vehicle/InitialConnectStateMachine.cc +++ b/src/Vehicle/InitialConnectStateMachine.cc @@ -21,6 +21,7 @@ QGC_LOGGING_CATEGORY(InitialConnectStateMachineLog, "InitialConnectStateMachineL const StateMachine::StateFn InitialConnectStateMachine::_rgStates[] = { InitialConnectStateMachine::_stateRequestAutopilotVersion, InitialConnectStateMachine::_stateRequestProtocolVersion, + InitialConnectStateMachine::_stateRequestStandardModes, InitialConnectStateMachine::_stateRequestCompInfo, InitialConnectStateMachine::_stateRequestParameters, InitialConnectStateMachine::_stateRequestMission, @@ -32,6 +33,7 @@ const StateMachine::StateFn InitialConnectStateMachine::_rgStates[] = { const int InitialConnectStateMachine::_rgProgressWeights[] = { 1, //_stateRequestCapabilities 1, //_stateRequestProtocolVersion + 1, //_stateRequestStandardModes 5, //_stateRequestCompInfo 5, //_stateRequestParameters 2, //_stateRequestMission @@ -282,6 +284,24 @@ void InitialConnectStateMachine::_stateRequestCompInfo(StateMachine* stateMachin vehicle->_componentInformationManager->requestAllComponentInformation(_stateRequestCompInfoComplete, connectMachine); } +void InitialConnectStateMachine::_stateRequestStandardModes(StateMachine *stateMachine) +{ + InitialConnectStateMachine* connectMachine = static_cast(stateMachine); + Vehicle* vehicle = connectMachine->_vehicle; + + qCDebug(InitialConnectStateMachineLog) << "_stateRequestStandardModes"; + connect(vehicle->_standardModes, &StandardModes::requestCompleted, connectMachine, + &InitialConnectStateMachine::standardModesRequestCompleted); + vehicle->_standardModes->request(); +} + +void InitialConnectStateMachine::standardModesRequestCompleted() +{ + disconnect(_vehicle->_standardModes, &StandardModes::requestCompleted, this, + &InitialConnectStateMachine::standardModesRequestCompleted); + advance(); +} + void InitialConnectStateMachine::_stateRequestCompInfoComplete(void* requestAllCompleteFnData) { InitialConnectStateMachine* connectMachine = static_cast(requestAllCompleteFnData); diff --git a/src/Vehicle/InitialConnectStateMachine.h b/src/Vehicle/InitialConnectStateMachine.h index 7218e39fe3d..44ed2e817ef 100644 --- a/src/Vehicle/InitialConnectStateMachine.h +++ b/src/Vehicle/InitialConnectStateMachine.h @@ -37,11 +37,13 @@ class InitialConnectStateMachine : public StateMachine private slots: void gotProgressUpdate(float progressValue); + void standardModesRequestCompleted(); private: static void _stateRequestAutopilotVersion (StateMachine* stateMachine); static void _stateRequestProtocolVersion (StateMachine* stateMachine); static void _stateRequestCompInfo (StateMachine* stateMachine); + static void _stateRequestStandardModes (StateMachine* stateMachine); static void _stateRequestCompInfoComplete (void* requestAllCompleteFnData); static void _stateRequestParameters (StateMachine* stateMachine); static void _stateRequestMission (StateMachine* stateMachine); diff --git a/src/Vehicle/StandardModes.cc b/src/Vehicle/StandardModes.cc new file mode 100644 index 00000000000..cdd5fcb9e5a --- /dev/null +++ b/src/Vehicle/StandardModes.cc @@ -0,0 +1,179 @@ +/**************************************************************************** + * + * (c) 2022 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "Vehicle.h" +#include "StandardModes.h" + +QGC_LOGGING_CATEGORY(StandardModesLog, "StandardModesLog") + + +static void requestMessageResultHandler(void* resultHandlerData, MAV_RESULT result, + Vehicle::RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t &message) +{ + StandardModes* standardModes = static_cast(resultHandlerData); + standardModes->gotMessage(result, message); +} + +StandardModes::StandardModes(QObject *parent, Vehicle *vehicle) + : QObject(parent), _vehicle(vehicle) +{ +} + +void StandardModes::gotMessage(MAV_RESULT result, const mavlink_message_t &message) +{ + _requestActive = false; + if (_wantReset) { + _wantReset = false; + request(); + return; + } + + if (result == MAV_RESULT_ACCEPTED) { + mavlink_available_modes_t availableModes; + mavlink_msg_available_modes_decode(&message, &availableModes); + bool cannotBeSet = availableModes.properties & MAV_MODE_PROPERTY_NOT_USER_SELECTABLE; + bool advanced = availableModes.properties & MAV_MODE_PROPERTY_ADVANCED; + availableModes.mode_name[sizeof(availableModes.mode_name)-1] = '\0'; + QString name = availableModes.mode_name; + switch (availableModes.standard_mode) { + case MAV_STANDARD_MODE_POSITION_HOLD: + name = "Position"; + break; + case MAV_STANDARD_MODE_ORBIT: + name = "Orbit"; + break; + case MAV_STANDARD_MODE_CRUISE: + name = "Cruise"; + break; + case MAV_STANDARD_MODE_ALTITUDE_HOLD: + name = "Altitude"; + break; + case MAV_STANDARD_MODE_RETURN_HOME: + name = "Return"; + break; + case MAV_STANDARD_MODE_SAFE_RECOVERY: + name = "Safe Recovery"; + break; + case MAV_STANDARD_MODE_MISSION: + name = "Mission"; + break; + case MAV_STANDARD_MODE_LAND: + name = "Land"; + break; + case MAV_STANDARD_MODE_TAKEOFF: + name = "Takeoff"; + break; + } + + if (name == "Takeoff" || name == "VTOL Takeoff" || name == "Orbit" || name == "Land" || name == "Return") { // These are exposed in the UI as separate buttons + cannotBeSet = true; + } + + qCDebug(StandardModesLog) << "Got mode:" << name << ", idx:" << availableModes.mode_index << ", custom_mode" << availableModes.custom_mode; + + _nextModes[availableModes.custom_mode] = Mode{name, availableModes.standard_mode, advanced, cannotBeSet}; + + if (availableModes.mode_index >= availableModes.number_modes) { // We are done + qCDebug(StandardModesLog) << "Completed, num modes:" << _nextModes.size(); + _modes = _nextModes; + ensureUniqueModeNames(); + _hasModes = true; + emit modesUpdated(); + emit requestCompleted(); + + } else { + requestMode(availableModes.mode_index + 1); + } + + } else { + qCDebug(StandardModesLog) << "Failed to retrieve available modes" << result; + emit requestCompleted(); + } +} + +void StandardModes::ensureUniqueModeNames() +{ + // Ensure mode names are unique. This should generally already be the case, but e.g. during development when + // restarting dynamic modes, it might not be. + for (auto iter = _modes.begin(); iter != _modes.end(); ++iter) { + int duplicateIdx = 0; + for (auto iter2 = iter + 1; iter2 != _modes.end(); ++iter2) { + if (iter.value().name == iter2.value().name) { + iter2.value().name += QStringLiteral(" (%1)").arg(duplicateIdx + 1); + ++duplicateIdx; + } + } + } +} + +void StandardModes::request() +{ + if (_requestActive) { + // If we are in the middle of waiting for a request, wait for the response first + _wantReset = true; + return; + } + + _nextModes.clear(); + + qCDebug(StandardModesLog) << "Requesting available modes"; + // Request one at a time. This could be improved by requesting all, but we can't use Vehicle::requestMessage for that + StandardModes::requestMode(1); +} + +void StandardModes::requestMode(int modeIndex) +{ + _requestActive = true; + _vehicle->requestMessage( + requestMessageResultHandler, + this, + MAV_COMP_ID_AUTOPILOT1, + MAVLINK_MSG_ID_AVAILABLE_MODES, modeIndex); +} + +void StandardModes::availableModesMonitorReceived(uint8_t seq) +{ + if (_lastSeq != seq) { + qCDebug(StandardModesLog) << "Available modes changed, re-requesting"; + _lastSeq = seq; + request(); + } +} + +QStringList StandardModes::flightModes() +{ + QStringList ret; + for (const auto& mode : _modes) { + if (mode.cannotBeSet) { + continue; + } + ret += mode.name; + } + return ret; +} + +QString StandardModes::flightMode(uint32_t custom_mode) const +{ + auto iter = _modes.find(custom_mode); + if (iter != _modes.end()) { + return iter->name; + } + return tr("Unknown %2").arg(custom_mode); +} + +bool StandardModes::setFlightMode(const QString &flightMode, uint32_t *custom_mode) +{ + for (auto iter = _modes.constBegin(); iter != _modes.constEnd(); ++iter) { + if (iter->name == flightMode) { + *custom_mode = iter.key(); + return true; + } + } + return false; +} diff --git a/src/Vehicle/StandardModes.h b/src/Vehicle/StandardModes.h new file mode 100644 index 00000000000..948511ad2d0 --- /dev/null +++ b/src/Vehicle/StandardModes.h @@ -0,0 +1,69 @@ +/**************************************************************************** + * + * (c) 2022 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +#include "QGCLoggingCategory.h" +#include "QGCMAVLink.h" +#include +#include + +Q_DECLARE_LOGGING_CATEGORY(StandardModesLog) + +class Vehicle; + +class StandardModes : public QObject +{ +Q_OBJECT + +public: + struct Mode { + QString name; + uint8_t standardMode; + bool advanced; + bool cannotBeSet; + }; + + StandardModes(QObject* parent, Vehicle* vehicle); + + void request(); + + void availableModesMonitorReceived(uint8_t seq); + + bool supported() const { return _hasModes; } + + QStringList flightModes(); + + QString flightMode(uint32_t custom_mode) const; + + bool setFlightMode(const QString& flightMode, uint32_t* custom_mode); + + void gotMessage(MAV_RESULT result, const mavlink_message_t &message); +signals: + void modesUpdated(); + void requestCompleted(); + +private: + + void requestMode(int modeIndex); + void ensureUniqueModeNames(); + + Vehicle*const _vehicle; + + bool _requestActive{false}; + bool _wantReset{false}; + QMap _nextModes; ///< Modes added by current request + + bool _hasModes{false}; + + int _lastSeq{-1}; + + QMap _modes; ///< key is custom_mode +}; + diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 0faa32593ca..1b2de23a80f 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -372,12 +372,15 @@ void Vehicle::_commonInit() connect(_missionManager, &MissionManager::sendComplete, _trajectoryPoints, &TrajectoryPoints::clear); connect(_missionManager, &MissionManager::newMissionItemsAvailable, _trajectoryPoints, &TrajectoryPoints::clear); + _standardModes = new StandardModes (this, this); _componentInformationManager = new ComponentInformationManager (this); _initialConnectStateMachine = new InitialConnectStateMachine (this); _ftpManager = new FTPManager (this); _imageProtocolManager = new ImageProtocolManager (); _vehicleLinkManager = new VehicleLinkManager (this); + connect(_standardModes, &StandardModes::modesUpdated, this, &Vehicle::flightModesChanged); + _parameterManager = new ParameterManager(this); connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady); @@ -762,6 +765,16 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes } } break; + case MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR: + { + // Avoid duplicate requests during initial connection setup + if (!_initialConnectStateMachine || !_initialConnectStateMachine->active()) { + mavlink_available_modes_monitor_t availableModesMonitor; + mavlink_msg_available_modes_monitor_decode(&message, &availableModesMonitor); + _standardModes->availableModesMonitorReceived(availableModesMonitor.seq); + } + break; + } // Following are ArduPilot dialect messages #if !defined(NO_ARDUPILOT_DIALECT) @@ -1677,7 +1690,7 @@ void Vehicle::setEventsMetadata(uint8_t compid, const QString& metadataJsonFileN for (size_t i = 0; i < sizeof(modeGroups)/sizeof(modeGroups[0]); ++i) { uint8_t base_mode; uint32_t custom_mode; - if (_firmwarePlugin->setFlightMode(modes[i], &base_mode, &custom_mode)) { + if (setFlightModeCustom(modes[i], &base_mode, &custom_mode)) { modeGroups[i] = _eventHandler(compid).getModeGroup(custom_mode); if (modeGroups[i] == -1) { qCDebug(VehicleLog) << "Failed to get mode group for mode" << modes[i] << "(Might not be in metadata)"; @@ -2182,20 +2195,35 @@ bool Vehicle::flightModeSetAvailable() QStringList Vehicle::flightModes() { + if (_standardModes->supported()) { + return _standardModes->flightModes(); + } return _firmwarePlugin->flightModes(this); } QString Vehicle::flightMode() const { + if (_standardModes->supported()) { + return _standardModes->flightMode(_custom_mode); + } return _firmwarePlugin->flightMode(_base_mode, _custom_mode); } +bool Vehicle::setFlightModeCustom(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) +{ + if (_standardModes->supported()) { + *base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; + return _standardModes->setFlightMode(flightMode, custom_mode); + } + return _firmwarePlugin->setFlightMode(flightMode, base_mode, custom_mode); +} + void Vehicle::setFlightMode(const QString& flightMode) { uint8_t base_mode; uint32_t custom_mode; - if (_firmwarePlugin->setFlightMode(flightMode, &base_mode, &custom_mode)) { + if (setFlightModeCustom(flightMode, &base_mode, &custom_mode)) { SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock(); if (!sharedLink) { qCDebug(VehicleLog) << "setFlightMode: primary link gone!"; diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 18acaecb4fc..32621927b84 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -48,6 +48,7 @@ #include "ImageProtocolManager.h" #include "HealthAndArmingCheckReport.h" #include "TerrainQuery.h" +#include "StandardModes.h" class Actuators; class EventHandler; @@ -1086,6 +1087,7 @@ private slots: void _chunkedStatusTextCompleted (uint8_t compId); void _setMessageInterval (int messageId, int rate); EventHandler& _eventHandler (uint8_t compid); + bool setFlightModeCustom (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode); static void _rebootCommandResultHandler(void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, MavCmdResultFailureCode_t failureCode); @@ -1401,6 +1403,7 @@ private slots: InitialConnectStateMachine* _initialConnectStateMachine = nullptr; Actuators* _actuators = nullptr; RemoteIDManager* _remoteIDManager = nullptr; + StandardModes* _standardModes = nullptr; static const char* _rollFactName; static const char* _pitchFactName; From 968db69d9e2baacdfa6b4210c39b773025126219 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 22 Mar 2023 07:50:42 +0100 Subject: [PATCH 065/118] Vehicle: handle MAVLINK_MSG_ID_CURRENT_MODE --- src/Vehicle/Vehicle.cc | 22 +++++++++++++++++++--- src/Vehicle/Vehicle.h | 3 +++ 2 files changed, 22 insertions(+), 3 deletions(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 1b2de23a80f..7af3bd6e367 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -775,6 +775,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes } break; } + case MAVLINK_MSG_ID_CURRENT_MODE: + _handleCurrentMode(message); + break; // Following are ArduPilot dialect messages #if !defined(NO_ARDUPILOT_DIALECT) @@ -1664,16 +1667,15 @@ EventHandler& Vehicle::_eventHandler(uint8_t compid) // connect health and arming check updates connect(eventHandler.data(), &EventHandler::healthAndArmingChecksUpdated, this, [compid, this]() { - // TODO: use user-intended mode instead of currently set mode const QSharedPointer& eventHandler = _events[compid]; _healthAndArmingCheckReport.update(compid, eventHandler->healthAndArmingCheckResults(), - eventHandler->getModeGroup(_custom_mode)); + eventHandler->getModeGroup(_has_custom_mode_user_intention ? _custom_mode_user_intention : _custom_mode)); }); connect(this, &Vehicle::flightModeChanged, this, [compid, this]() { const QSharedPointer& eventHandler = _events[compid]; if (eventHandler->healthAndArmingCheckResultsValid()) { _healthAndArmingCheckReport.update(compid, eventHandler->healthAndArmingCheckResults(), - eventHandler->getModeGroup(_custom_mode)); + eventHandler->getModeGroup(_has_custom_mode_user_intention ? _custom_mode_user_intention : _custom_mode)); } }); } @@ -1753,6 +1755,20 @@ void Vehicle::_handleHeartbeat(mavlink_message_t& message) } } +void Vehicle::_handleCurrentMode(mavlink_message_t& message) +{ + mavlink_current_mode_t currentMode; + mavlink_msg_current_mode_decode(&message, ¤tMode); + if (currentMode.intended_custom_mode != 0) { // 0 == unknown/not supplied + _has_custom_mode_user_intention = true; + bool changed = _custom_mode_user_intention != currentMode.intended_custom_mode; + _custom_mode_user_intention = currentMode.intended_custom_mode; + if (changed) { + emit flightModeChanged(flightMode()); + } + } +} + void Vehicle::_handleRadioStatus(mavlink_message_t& message) { diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 32621927b84..d9297088410 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -1036,6 +1036,7 @@ private slots: void _handlePing (LinkInterface* link, mavlink_message_t& message); void _handleHomePosition (mavlink_message_t& message); void _handleHeartbeat (mavlink_message_t& message); + void _handleCurrentMode (mavlink_message_t& message); void _handleRadioStatus (mavlink_message_t& message); void _handleRCChannels (mavlink_message_t& message); void _handleBatteryStatus (mavlink_message_t& message); @@ -1181,6 +1182,8 @@ private slots: bool _armed = false; ///< true: vehicle is armed uint8_t _base_mode = 0; ///< base_mode from HEARTBEAT uint32_t _custom_mode = 0; ///< custom_mode from HEARTBEAT + uint32_t _custom_mode_user_intention = 0; ///< custom_mode_user_intention from CURRENT_MODE + bool _has_custom_mode_user_intention = false; /// Used to store a message being sent by sendMessageMultiple typedef struct { From 427a5c43fc8cc42e80e2b81d3a7ee424d32d6806 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 28 Jul 2023 07:31:32 +0200 Subject: [PATCH 066/118] joystick: handle dynamic flight mode updates --- src/Joystick/Joystick.cc | 7 +++++++ src/Joystick/Joystick.h | 2 +- 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index e138739eeca..b9835c47696 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -222,6 +222,10 @@ void Joystick::_activeVehicleChanged(Vehicle* activeVehicle) setTXMode(mode); } } +void Joystick::_flightModesChanged() +{ + _buildActionList(_activeVehicle); +} void Joystick::_vehicleCountChanged(int count) { @@ -717,6 +721,7 @@ void Joystick::startPolling(Vehicle* vehicle) disconnect(this, &Joystick::gimbalControlValue, _activeVehicle, &Vehicle::gimbalControlValue); disconnect(this, &Joystick::emergencyStop, _activeVehicle, &Vehicle::emergencyStop); disconnect(this, &Joystick::gripperAction, _activeVehicle, &Vehicle::setGripperAction); + disconnect(_activeVehicle, &Vehicle::flightModesChanged, this, &Joystick::_flightModesChanged); } // Always set up the new vehicle _activeVehicle = vehicle; @@ -740,6 +745,7 @@ void Joystick::startPolling(Vehicle* vehicle) connect(this, &Joystick::gimbalControlValue, _activeVehicle, &Vehicle::gimbalControlValue); connect(this, &Joystick::emergencyStop, _activeVehicle, &Vehicle::emergencyStop); connect(this, &Joystick::gripperAction, _activeVehicle, &Vehicle::setGripperAction); + connect(_activeVehicle, &Vehicle::flightModesChanged, this, &Joystick::_flightModesChanged); } } if (!isRunning()) { @@ -760,6 +766,7 @@ void Joystick::stopPolling(void) disconnect(this, &Joystick::centerGimbal, _activeVehicle, &Vehicle::centerGimbal); disconnect(this, &Joystick::gimbalControlValue, _activeVehicle, &Vehicle::gimbalControlValue); disconnect(this, &Joystick::gripperAction, _activeVehicle, &Vehicle::setGripperAction); + disconnect(_activeVehicle, &Vehicle::flightModesChanged, this, &Joystick::_flightModesChanged); } _exitThread = true; } diff --git a/src/Joystick/Joystick.h b/src/Joystick/Joystick.h index 2c6f2893d8b..74056303dae 100644 --- a/src/Joystick/Joystick.h +++ b/src/Joystick/Joystick.h @@ -366,5 +366,5 @@ class Joystick : public QThread private slots: void _activeVehicleChanged(Vehicle* activeVehicle); void _vehicleCountChanged(int count); - + void _flightModesChanged(); }; From c002ef6f702be1a0ec52914754ab898e3f0e538b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 3 Aug 2023 10:54:04 +0200 Subject: [PATCH 067/118] StandardModes: only enable for daily builds --- src/Vehicle/StandardModes.cc | 4 ++++ src/Vehicle/Vehicle.cc | 4 +++- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/src/Vehicle/StandardModes.cc b/src/Vehicle/StandardModes.cc index cdd5fcb9e5a..e58ca907383 100644 --- a/src/Vehicle/StandardModes.cc +++ b/src/Vehicle/StandardModes.cc @@ -114,6 +114,7 @@ void StandardModes::ensureUniqueModeNames() void StandardModes::request() { +#ifdef DAILY_BUILD // Disable use of development/WIP MAVLink messages for release builds if (_requestActive) { // If we are in the middle of waiting for a request, wait for the response first _wantReset = true; @@ -125,6 +126,9 @@ void StandardModes::request() qCDebug(StandardModesLog) << "Requesting available modes"; // Request one at a time. This could be improved by requesting all, but we can't use Vehicle::requestMessage for that StandardModes::requestMode(1); +#else + emit requestCompleted(); +#endif // DAILY_BUILD } void StandardModes::requestMode(int modeIndex) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 7af3bd6e367..d6530135858 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -765,7 +765,8 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes } } break; - case MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR: +#ifdef DAILY_BUILD // Disable use of development/WIP MAVLink messages for release builds + case MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR: { // Avoid duplicate requests during initial connection setup if (!_initialConnectStateMachine || !_initialConnectStateMachine->active()) { @@ -778,6 +779,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes case MAVLINK_MSG_ID_CURRENT_MODE: _handleCurrentMode(message); break; +#endif // DAILY_BUILD // Following are ArduPilot dialect messages #if !defined(NO_ARDUPILOT_DIALECT) From 1cfc3736c38e1e65bc6e2a32f76938f6f223459c Mon Sep 17 00:00:00 2001 From: Zdanek Date: Fri, 22 Sep 2023 14:12:26 +0200 Subject: [PATCH 068/118] Set instrument Value have custom color as label Fix instrument panel and editor layout --- src/QmlControls/InstrumentValueEditDialog.qml | 12 +++++++++--- src/QmlControls/InstrumentValueLabel.qml | 6 +++--- src/QmlControls/InstrumentValueValue.qml | 1 + 3 files changed, 13 insertions(+), 6 deletions(-) diff --git a/src/QmlControls/InstrumentValueEditDialog.qml b/src/QmlControls/InstrumentValueEditDialog.qml index 6f3e37a8628..7d45d9f3e69 100644 --- a/src/QmlControls/InstrumentValueEditDialog.qml +++ b/src/QmlControls/InstrumentValueEditDialog.qml @@ -192,13 +192,19 @@ QGCPopupDialog { case InstrumentValueData.OpacityRange: sourceComponent = opacityRangeDialog break - case InstrumentValueData.IconSelvalueedectRange: + case InstrumentValueData.IconSelectRange: sourceComponent = iconRangeDialog break } } - Component.onCompleted: updateSourceComponent() + Component.onCompleted: { + updateSourceComponent() + if (sourceComponent) { + height = item.childrenRect.height + width = item.childrenRect.width + } + } Connections { target: instrumentValueData @@ -329,7 +335,7 @@ QGCPopupDialog { id: iconRangeDialog Item { - width: childrenRect.widthvalueed + width: childrenRect.width height: childrenRect.height function updateRangeValue(index, text) { diff --git a/src/QmlControls/InstrumentValueLabel.qml b/src/QmlControls/InstrumentValueLabel.qml index 7ec8b370d73..99e09c780dd 100644 --- a/src/QmlControls/InstrumentValueLabel.qml +++ b/src/QmlControls/InstrumentValueLabel.qml @@ -36,7 +36,7 @@ ColumnLayout { id: valueIcon Layout.alignment: _verticalOrientation ? Qt.AlignHCenter : Qt.AlignVCenter height: _tightHeight * 0.75 - width: height + width: _tightHeight * 0.85 sourceSize.height: height fillMode: Image.PreserveAspectFit mipmap: true @@ -50,9 +50,9 @@ ColumnLayout { function updateIcon() { if (instrumentValueData.rangeType === InstrumentValueData.IconSelectRange) { - valueIcon.source = iconPrefix + instrumentValueData.currentIcon + valueIcon.source = instrumentValueData.currentIcon != "" ? iconPrefix + instrumentValueData.currentIcon : ""; } else if (instrumentValueData.icon) { - valueIcon.source = iconPrefix + instrumentValueData.icon + valueIcon.source = instrumentValueData.icon != "" ? iconPrefix + instrumentValueData.icon : ""; } else { valueIcon.source = "" } diff --git a/src/QmlControls/InstrumentValueValue.qml b/src/QmlControls/InstrumentValueValue.qml index 2d8e107606a..7b2a3302d1d 100644 --- a/src/QmlControls/InstrumentValueValue.qml +++ b/src/QmlControls/InstrumentValueValue.qml @@ -38,6 +38,7 @@ ColumnLayout { id: label Layout.alignment: Qt.AlignVCenter font.pointSize: _fontSize + color: instrumentValueData.isValidColor(instrumentValueData.currentColor) ? instrumentValueData.currentColor : qgcPal.text text: valueText() function valueText() { From a0efba36b4ba0eb157ee2c80884608e440c85d11 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Tue, 17 Oct 2023 17:38:52 +0200 Subject: [PATCH 069/118] MissionManager: Support for MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW --- src/MissionManager/MavCmdInfoCommon.json | 45 ++++++++++++++++++++++++ src/MissionManager/MissionController.cc | 1 + 2 files changed, 46 insertions(+) diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json index 74210374c67..30ff4678808 100644 --- a/src/MissionManager/MavCmdInfoCommon.json +++ b/src/MissionManager/MavCmdInfoCommon.json @@ -910,6 +910,51 @@ "enumValues": "0,1,2,3,4" } }, + { + "id": 1000, + "rawName": "MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW", + "friendlyName": "Gimbal Manager PitchYaw" , + "description": "Control the gimbal during the mission", + "category": "Advanced", + "param1": { + "label": "Pitch", + "default": 0, + "units": "deg", + "decimalPlaces": 2 + }, + "param2": { + "label": "Yaw", + "default": 0, + "units": "deg", + "decimalPlaces": 2 + }, + "param3": { + "label": "Pitch rate", + "default": 0, + "units": "deg/s", + "decimalPlaces": 2 + }, + "param4": { + "label": "Yaw rate", + "default": 0, + "units": "deg/s", + "decimalPlaces": 2 + }, + "param5": { + "label": "Follow yaw", + "default": 0, + "decimalPlaces": 0, + "enumStrings": "Follow yaw, Lock yaw", + "enumValues": "0,16" + }, + "param7": { + "label": "Gimbal", + "default": 0, + "decimalPlaces": 0, + "enumStrings": "Primary,first gimbal,second gimbal", + "enumValues": "0,1,2" + } + }, { "id": 206, "rawName": "MAV_CMD_DO_SET_CAM_TRIGG_DIST", diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index ba6d9a039e7..4f482c082e3 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -1576,6 +1576,7 @@ void MissionController::_recalcMissionFlightStatus() case MAV_CMD_NAV_ROI: case MAV_CMD_DO_SET_ROI_LOCATION: case MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET: + case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: _missionFlightStatus.gimbalYaw = qQNaN(); _missionFlightStatus.gimbalPitch = qQNaN(); break; From d0ef9ea8568e6190760ec09aa644c74cf7132ba3 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Tue, 17 Oct 2023 10:32:08 +0200 Subject: [PATCH 070/118] PhotoVideoControl.qml: Fix toggleShotting when no mavlink camera --- src/FlightMap/Widgets/PhotoVideoControl.qml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/FlightMap/Widgets/PhotoVideoControl.qml b/src/FlightMap/Widgets/PhotoVideoControl.qml index 558c3b19d05..c81b7b41a36 100644 --- a/src/FlightMap/Widgets/PhotoVideoControl.qml +++ b/src/FlightMap/Widgets/PhotoVideoControl.qml @@ -101,7 +101,7 @@ Rectangle { function toggleShooting() { console.log("toggleShooting", _anyVideoStreamAvailable) - if (_mavlinkCamera && _mavlinkCamera.capturesVideo || _mavlinkCamera.capturesPhotos ) { + if (_mavlinkCamera && (_mavlinkCamera.capturesVideo || _mavlinkCamera.capturesPhotos) ) { if(_mavlinkCameraInVideoMode) { _mavlinkCamera.toggleVideo() } else { From b0859bd13bbe7d90b8d0453981719e5160d136a0 Mon Sep 17 00:00:00 2001 From: Sergii Lisovenko <2522054+s-lisovenko@users.noreply.github.com> Date: Sun, 15 Oct 2023 08:29:48 +0300 Subject: [PATCH 071/118] Optimize map provider iteration to prevent app crashes Changed from QHashIterator to using a constant iterator for iterating through the map providers in _providersTable. This change prevents application crashes during a map download session caused by the potential modification of an implicitly shared hash. --- src/QtLocationPlugin/QGCMapUrlEngine.cpp | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.cpp b/src/QtLocationPlugin/QGCMapUrlEngine.cpp index 7f4cbfd02b5..b41002fbb08 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.cpp +++ b/src/QtLocationPlugin/QGCMapUrlEngine.cpp @@ -156,13 +156,9 @@ quint32 UrlFactory::averageSizeForType(const QString& type) { } QString UrlFactory::getTypeFromId(int id) { - - QHashIterator i(_providersTable); - - while (i.hasNext()) { - i.next(); - if ((int)(qHash(i.key())>>1) == id) { - return i.key(); + for (auto it = _providersTable.constBegin(); it != _providersTable.constEnd(); ++it) { + if ((int)(qHash(it.key()) >> 1) == id) { + return it.key(); } } qCDebug(QGCMapUrlEngineLog) << "getTypeFromId : id not found" << id; From 08d0bc2496403caedcf9af3011919b316693884c Mon Sep 17 00:00:00 2001 From: Oleksiy Protas Date: Thu, 31 Aug 2023 23:19:43 +0300 Subject: [PATCH 072/118] H.265(HEVC) decoder ranking adjusted for VA-API and libav Only gstreamer-vaapi plugin modules addressed as in the original code. Possibly need to have va plugin support too, but on a lower rank. --- src/VideoReceiver/GStreamer.cc | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/VideoReceiver/GStreamer.cc b/src/VideoReceiver/GStreamer.cc index 0515d6ac7f2..4fe2b103e15 100644 --- a/src/VideoReceiver/GStreamer.cc +++ b/src/VideoReceiver/GStreamer.cc @@ -136,10 +136,12 @@ GStreamer::blacklist(VideoSettings::VideoDecoderOptions option) case VideoSettings::ForceVideoDecoderDefault: break; case VideoSettings::ForceVideoDecoderSoftware: - changeRank("avdec_h264", GST_RANK_PRIMARY + 1); + for(auto name : {"avdec_h264", "avdec_h265"}) { + changeRank(name, GST_RANK_PRIMARY + 1); + } break; case VideoSettings::ForceVideoDecoderVAAPI: - for(auto name : {"vaapimpeg2dec", "vaapimpeg4dec", "vaapih263dec", "vaapih264dec", "vaapivc1dec"}) { + for(auto name : {"vaapimpeg2dec", "vaapimpeg4dec", "vaapih263dec", "vaapih264dec", "vaapih265dec", "vaapivc1dec"}) { changeRank(name, GST_RANK_PRIMARY + 1); } break; From a6f14d580692fd11974decd8d5e0274c88781dc5 Mon Sep 17 00:00:00 2001 From: Colin Wong Date: Fri, 20 Oct 2023 19:31:24 -0500 Subject: [PATCH 073/118] Fix typo in Fahrenheit name --- src/Settings/UnitsSettings.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Settings/UnitsSettings.cc b/src/Settings/UnitsSettings.cc index 90d496d61fb..e290c17841e 100644 --- a/src/Settings/UnitsSettings.cc +++ b/src/Settings/UnitsSettings.cc @@ -155,7 +155,7 @@ DECLARE_SETTINGSFACT_NO_FUNC(UnitsSettings, temperatureUnits) // Units settings can't be loaded from json since it creates an infinite loop of meta data loading. QStringList enumStrings; QVariantList enumValues; - enumStrings << "Celsius" << "Farenheit"; + enumStrings << "Celsius" << "Fahrenheit"; enumValues << QVariant::fromValue(static_cast(TemperatureUnitsCelsius)) << QVariant::fromValue(static_cast(TemperatureUnitsFarenheit)); FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this); metaData->setName(temperatureUnitsName); From 0fb6a9cea3f370d150d867e3e05f55324469083a Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Tue, 31 Oct 2023 14:27:50 +0000 Subject: [PATCH 074/118] Update PX4 Firmware metadata Tue Oct 31 14:27:50 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index bdcaa25597b..52e82161395 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -7593,6 +7593,10 @@ + + RTL force approach landing + Only consider RTL point, if it has an approach defined. + RTL time estimate safety margin factor Safety factor that is used to scale the actual RTL time estimate. Time with margin = RTL_TIME_FACTOR * time + RTL_TIME_MARGIN From bf7c68942f93e4ec3d087c595fe820b07f030a24 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 1 Nov 2023 11:43:31 +1100 Subject: [PATCH 075/118] APM: cope with IN_PROGRESS messages from autopilot --- src/AutoPilotPlugins/APM/APMSensorsComponentController.cc | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc index 91a5190fdf1..fbd53d05bfc 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc @@ -524,6 +524,9 @@ void APMSensorsComponentController::_handleCommandAck(mavlink_message_t& message if (commandAck.command == MAV_CMD_PREFLIGHT_CALIBRATION) { switch (commandAck.result) { + case MAV_RESULT_IN_PROGRESS: + _appendStatusLog(tr("In progress")); + break; case MAV_RESULT_ACCEPTED: _appendStatusLog(tr("Successfully completed")); _stopCalibration(StopCalibrationSuccessShowLog); From 22f0898fd3bf8db39ad882e9364ed96cb307b7de Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 30 Oct 2023 12:59:29 -0700 Subject: [PATCH 076/118] Hardware: Add support for Pixhawk FMUv6XRT --- src/VehicleSetup/FirmwareUpgradeController.cc | 1 + src/comm/USBBoardInfo.json | 3 +++ 2 files changed, 4 insertions(+) diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/VehicleSetup/FirmwareUpgradeController.cc index 303a9086603..7524a12e06f 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.cc +++ b/src/VehicleSetup/FirmwareUpgradeController.cc @@ -62,6 +62,7 @@ static QMap px4_board_name_map { {54, "px4_fmu-v6u_default"}, {56, "px4_fmu-v6c_default"}, {57, "ark_fmu-v6x_default"}, + {58, "px4_fmu-v6xrt_default"}, {55, "sky-drones_smartap-airlink_default"}, {88, "airmind_mindpx-v2_default"}, {12, "bitcraze_crazyflie_default"}, diff --git a/src/comm/USBBoardInfo.json b/src/comm/USBBoardInfo.json index 3bbc918bb1e..8c99ed504d4 100644 --- a/src/comm/USBBoardInfo.json +++ b/src/comm/USBBoardInfo.json @@ -17,6 +17,7 @@ { "vendorID": 7052, "productID": 54, "boardClass": "Pixhawk", "name": "PX4 FMU V6U" }, { "vendorID": 12677, "productID": 53, "boardClass": "Pixhawk", "name": "PX4 FMU V6X" }, { "vendorID": 12677, "productID": 56, "boardClass": "Pixhawk", "name": "PX4 FMU V6C" }, + { "vendorID": 3643, "productID": 29, "boardClass": "Pixhawk", "name": "PX4 FMU V6X-RT" }, { "vendorID": 9900, "productID": 64, "boardClass": "Pixhawk", "name": "TAP V1" }, { "vendorID": 9900, "productID": 65, "boardClass": "Pixhawk", "name": "ASC V1" }, { "vendorID": 9900, "productID": 22, "boardClass": "Pixhawk", "name": "Crazyflie 2" }, @@ -63,6 +64,8 @@ { "regExp": "^PX4 BL FMU v6U.x$", "boardClass": "Pixhawk" }, { "regExp": "^PX4 FMU v6X.x$", "boardClass": "Pixhawk" }, { "regExp": "^PX4 BL FMU v6X.x$", "boardClass": "Pixhawk" }, + { "regExp": "^PX4 FMU v6XRT.x$", "boardClass": "Pixhawk" }, + { "regExp": "^PX4 BL FMU v6XRT.x$", "boardClass": "Pixhawk" }, { "regExp": "^PX4 FMU v5X.x$", "boardClass": "Pixhawk" }, { "regExp": "^PX4 BL FMU v5X.x$", "boardClass": "Pixhawk" }, { "regExp": "^PX4 FMU v5.x$", "boardClass": "Pixhawk" }, From d072f32a85875a769bc6a2dc3b2803d438a2f9e2 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Tue, 31 Oct 2023 08:43:52 -0700 Subject: [PATCH 077/118] Update USBBoardInfo.json --- src/comm/USBBoardInfo.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/comm/USBBoardInfo.json b/src/comm/USBBoardInfo.json index 8c99ed504d4..813a5cb0893 100644 --- a/src/comm/USBBoardInfo.json +++ b/src/comm/USBBoardInfo.json @@ -17,7 +17,7 @@ { "vendorID": 7052, "productID": 54, "boardClass": "Pixhawk", "name": "PX4 FMU V6U" }, { "vendorID": 12677, "productID": 53, "boardClass": "Pixhawk", "name": "PX4 FMU V6X" }, { "vendorID": 12677, "productID": 56, "boardClass": "Pixhawk", "name": "PX4 FMU V6C" }, - { "vendorID": 3643, "productID": 29, "boardClass": "Pixhawk", "name": "PX4 FMU V6X-RT" }, + { "vendorID": 13891, "productID": 29, "boardClass": "Pixhawk", "name": "PX4 FMU V6X-RT" }, { "vendorID": 9900, "productID": 64, "boardClass": "Pixhawk", "name": "TAP V1" }, { "vendorID": 9900, "productID": 65, "boardClass": "Pixhawk", "name": "ASC V1" }, { "vendorID": 9900, "productID": 22, "boardClass": "Pixhawk", "name": "Crazyflie 2" }, From b871751e625f48ba030264c9629bd2373fb15a2d Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Wed, 1 Nov 2023 14:25:05 +0000 Subject: [PATCH 078/118] Remove android sdks newer than 33 This will force gradle to use sdsk 33 only --- .github/workflows/android_release.yml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/workflows/android_release.yml b/.github/workflows/android_release.yml index c007fc63b38..f889e0a6ce4 100644 --- a/.github/workflows/android_release.yml +++ b/.github/workflows/android_release.yml @@ -63,10 +63,12 @@ jobs: ndk-version: r21e add-to-path: false - - name: Remove Android SDK android-33-ext + - name: Remove Android SDKs to force usage of android-33 only run: | ${ANDROID_SDK_ROOT}/cmdline-tools/latest/bin/sdkmanager --uninstall "platforms;android-33-ext5" ${ANDROID_SDK_ROOT}/cmdline-tools/latest/bin/sdkmanager --uninstall "platforms;android-33-ext4" + ${ANDROID_SDK_ROOT}/cmdline-tools/latest/bin/sdkmanager --uninstall "platforms;android-34" + ${ANDROID_SDK_ROOT}/cmdline-tools/latest/bin/sdkmanager --uninstall "platforms;android-34-ext8" - name: Install ccache run: sudo apt-get install ccache From 39b345e63601b0666ffe20a1aa6f7cd85cd9e077 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 31 Oct 2023 14:26:15 +0100 Subject: [PATCH 079/118] Vehicle: update mode when StandardModes::modesUpdated is emitted Required because the label of the currently active mode might change. E.g. when an external mode gets registered but was already selected. --- src/Vehicle/Vehicle.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index d6530135858..3d2a3612ec1 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -380,6 +380,7 @@ void Vehicle::_commonInit() _vehicleLinkManager = new VehicleLinkManager (this); connect(_standardModes, &StandardModes::modesUpdated, this, &Vehicle::flightModesChanged); + connect(_standardModes, &StandardModes::modesUpdated, this, [this](){ Vehicle::flightModeChanged(flightMode()); }); _parameterManager = new ParameterManager(this); connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady); From a58fab96a83f0d1c516f89e42333e1ffc4c9d4fe Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 26 Oct 2023 12:48:04 +1100 Subject: [PATCH 080/118] Vehicle: add sendMavCommandIntWithHandler equivalent to the non-int function, allows a caller to specify a callback when ACK is received --- src/Vehicle/Vehicle.cc | 12 ++++++++++++ src/Vehicle/Vehicle.h | 5 +++++ 2 files changed, 17 insertions(+) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 3d2a3612ec1..a82fa790dae 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3006,6 +3006,18 @@ void Vehicle::sendMavCommandInt(int compId, MAV_CMD command, MAV_FRAME frame, bo param1, param2, param3, param4, param5, param6, param7); } +void Vehicle::sendMavCommandIntWithHandler(MavCmdResultHandler resultHandler, void *resultHandlerData, int compId, MAV_CMD command, MAV_FRAME frame, float param1, float param2, float param3, float param4, double param5, double param6, float param7) +{ + _sendMavCommandWorker(true, // commandInt + false, // showError + resultHandler, + resultHandlerData, + compId, + command, + frame, + param1, param2, param3, param4, param5, param6, param7); +} + bool Vehicle::isMavCommandPending(int targetCompId, MAV_CMD command) { return ((-1) < _findMavCommandListEntryIndex(targetCompId, command)); diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index d9297088410..1eb292fa4fc 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -774,6 +774,11 @@ class Vehicle : public FactGroup /// @param resultHandleData Opaque data passed through callback void sendMavCommandWithHandler(MavCmdResultHandler resultHandler, void* resultHandlerData, int compId, MAV_CMD command, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f); + /// Sends the command and calls the callback with the result + /// @param resultHandler Callback for result, nullptr for no callback + /// @param resultHandleData Opaque data passed through callback + void sendMavCommandIntWithHandler(MavCmdResultHandler resultHandler, void* resultHandlerData, int compId, MAV_CMD command, MAV_FRAME frame, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, double param5 = 0.0f, double param6 = 0.0f, float param7 = 0.0f); + typedef enum { RequestMessageNoFailure, RequestMessageFailureCommandError, From f79b466ffe166649e5a889596bc992721a8cdbd9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 26 Oct 2023 12:48:54 +1100 Subject: [PATCH 081/118] APMFirmwarePlugin: reposition using MAV_CMD_DO_REPOSITION ... falls back to using old mission-item method if reposition is not supported, which it is not for Sub --- src/FirmwarePlugin/APM/APMFirmwarePlugin.cc | 58 +++++++++++++++++++++ src/FirmwarePlugin/APM/APMFirmwarePlugin.h | 3 ++ 2 files changed, 61 insertions(+) diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 185a521cf9f..f38ffea1548 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -773,6 +773,31 @@ void APMFirmwarePlugin::pauseVehicle(Vehicle* vehicle) _setFlightModeAndValidate(vehicle, pauseFlightMode()); } +typedef struct { + Vehicle* vehicle; +} MAV_CMD_DO_REPOSITION_HandlerData_t; + +static void _MAV_CMD_DO_REPOSITION_ResultHandler(void* resultHandlerData, int /*compId*/, MAV_RESULT commandResult, uint8_t progress, Vehicle::MavCmdResultFailureCode_t failureCode) +{ + Q_UNUSED(progress); + + auto* data = (MAV_CMD_DO_REPOSITION_HandlerData_t*)resultHandlerData; + auto* vehicle = data->vehicle; + auto* instanceData = qobject_cast(vehicle->firmwarePluginInstanceData()); + + if (instanceData->MAV_CMD_DO_REPOSITION_supported || + instanceData->MAV_CMD_DO_REPOSITION_unsupported) { + // we never change out minds once set + goto out; + } + + instanceData->MAV_CMD_DO_REPOSITION_supported = (commandResult == MAV_RESULT_ACCEPTED); + instanceData->MAV_CMD_DO_REPOSITION_unsupported = (commandResult == MAV_RESULT_UNSUPPORTED); + +out: + delete data; +} + void APMFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) { if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) { @@ -780,6 +805,39 @@ void APMFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord return; } + // attempt to use MAV_CMD_DO_REPOSITION to move vehicle. If that + // comes back as unsupported, try using the old system of sending + // through mission items with custom "current" field values. + auto* instanceData = qobject_cast(vehicle->firmwarePluginInstanceData()); + + // if we know it is supported or we don't know for sure it is + // unsupported then send the command: + if (instanceData) { + if (instanceData->MAV_CMD_DO_REPOSITION_supported || + !instanceData->MAV_CMD_DO_REPOSITION_unsupported) { + auto* result_handler_data = new MAV_CMD_DO_REPOSITION_HandlerData_t{ + vehicle + }; + vehicle->sendMavCommandIntWithHandler( + _MAV_CMD_DO_REPOSITION_ResultHandler, + result_handler_data, + vehicle->defaultComponentId(), + MAV_CMD_DO_REPOSITION, + MAV_FRAME_GLOBAL, + -1.0f, + MAV_DO_REPOSITION_FLAGS_CHANGE_MODE, + 0.0f, + NAN, + gotoCoord.latitude(), + gotoCoord.longitude(), + vehicle->altitudeAMSL()->rawValue().toFloat() + ); + } + if (instanceData->MAV_CMD_DO_REPOSITION_supported) { + // no need to fall back + return; + } + } setGuidedMode(vehicle, true); diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index f4587f94137..4a1dd068673 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -137,4 +137,7 @@ class APMFirmwarePluginInstanceData : public QObject QTime lastBatteryStatusTime; QTime lastHomePositionTime; + + bool MAV_CMD_DO_REPOSITION_supported = false; + bool MAV_CMD_DO_REPOSITION_unsupported = false; }; From d69e66ccd081f88adbc4e75b30bee49ff3874658 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 24 Oct 2023 14:46:27 +1100 Subject: [PATCH 082/118] AutoPilotPlugins: remove APMCompassCal ArduPilot's onboard calibration is superior to this old-style "offboard compass calibration", and we've just merged a patch which removes the mavlink API call to set the sensor offsets into the ArduPilot master branch. --- src/AutoPilotPlugins/APM/APMCompassCal.cc | 690 ------------------ src/AutoPilotPlugins/APM/APMCompassCal.h | 168 ----- .../APM/APMSensorsComponent.qml | 3 - .../APM/APMSensorsComponentController.cc | 12 +- .../APM/APMSensorsComponentController.h | 3 - src/AutoPilotPlugins/CMakeLists.txt | 1 - 6 files changed, 1 insertion(+), 876 deletions(-) delete mode 100644 src/AutoPilotPlugins/APM/APMCompassCal.cc delete mode 100644 src/AutoPilotPlugins/APM/APMCompassCal.h diff --git a/src/AutoPilotPlugins/APM/APMCompassCal.cc b/src/AutoPilotPlugins/APM/APMCompassCal.cc deleted file mode 100644 index 23a43596665..00000000000 --- a/src/AutoPilotPlugins/APM/APMCompassCal.cc +++ /dev/null @@ -1,690 +0,0 @@ -/**************************************************************************** - * - * (c) 2009-2020 QGROUNDCONTROL PROJECT - * - * QGroundControl is licensed according to the terms in the file - * COPYING.md in the root of the source code directory. - * - ****************************************************************************/ - - -#include "APMCompassCal.h" -#include "AutoPilotPlugin.h" -#include "ParameterManager.h" - -QGC_LOGGING_CATEGORY(APMCompassCalLog, "APMCompassCalLog") - -const float CalWorkerThread::mag_sphere_radius = 0.2f; -const unsigned int CalWorkerThread::calibration_sides = 6; -const unsigned int CalWorkerThread::calibration_total_points = 240; -const unsigned int CalWorkerThread::calibraton_duration_seconds = CalWorkerThread::calibration_sides * 10; - -const char* CalWorkerThread::rgCompassParams[3][4] = { - { "COMPASS_OFS_X", "COMPASS_OFS_Y", "COMPASS_OFS_Z", "COMPASS_DEV_ID" }, - { "COMPASS_OFS2_X", "COMPASS_OFS2_Y", "COMPASS_OFS2_Z", "COMPASS_DEV_ID2" }, - { "COMPASS_OFS3_X", "COMPASS_OFS3_Y", "COMPASS_OFS3_Z", "COMPASS_DEV_ID3" }, -}; - -CalWorkerThread::CalWorkerThread(Vehicle* vehicle, QObject* parent) - : QThread(parent) - , _vehicle(vehicle) - , _cancel(false) -{ - -} - -void CalWorkerThread::run(void) -{ - if (calibrate() == calibrate_return_ok) { - _emitVehicleTextMessage(QStringLiteral("[cal] progress <100>")); - _emitVehicleTextMessage(QStringLiteral("[cal] calibration done: mag")); - } -} - -void CalWorkerThread::_emitVehicleTextMessage(const QString& message) -{ - emit vehicleTextMessage(_vehicle->id(), 0, MAV_SEVERITY_INFO, message); - qCDebug(APMCompassCalLog) << message; -} - -unsigned CalWorkerThread::progress_percentage(mag_worker_data_t* worker_data) -{ - return 100 * ((float)worker_data->done_count) / calibration_sides; -} - -CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void) -{ - calibrate_return result = calibrate_return_ok; - - mag_worker_data_t worker_data; - - worker_data.done_count = 0; - worker_data.calibration_points_perside = calibration_total_points / calibration_sides; - worker_data.calibration_interval_perside_seconds = calibraton_duration_seconds / calibration_sides; - worker_data.calibration_interval_perside_useconds = worker_data.calibration_interval_perside_seconds * 1000 * 1000; - - // Collect data for all sides - worker_data.side_data_collected[DETECT_ORIENTATION_RIGHTSIDE_UP] = false; - worker_data.side_data_collected[DETECT_ORIENTATION_LEFT] = false; - worker_data.side_data_collected[DETECT_ORIENTATION_NOSE_DOWN] = false; - worker_data.side_data_collected[DETECT_ORIENTATION_TAIL_DOWN] = false; - worker_data.side_data_collected[DETECT_ORIENTATION_UPSIDE_DOWN] = false; - worker_data.side_data_collected[DETECT_ORIENTATION_RIGHT] = false; - - for (size_t cur_mag=0; cur_mag(malloc(sizeof(float) * calibration_points_maxcount)); - worker_data.y[cur_mag] = reinterpret_cast(malloc(sizeof(float) * calibration_points_maxcount)); - worker_data.z[cur_mag] = reinterpret_cast(malloc(sizeof(float) * calibration_points_maxcount)); - if (worker_data.x[cur_mag] == nullptr || worker_data.y[cur_mag] == nullptr || worker_data.z[cur_mag] == nullptr) { - _emitVehicleTextMessage(QStringLiteral("[cal] ERROR: out of memory")); - result = calibrate_return_error; - } - } - } - - if (result == calibrate_return_ok) { - result = calibrate_from_orientation( - worker_data.side_data_collected, // Sides to calibrate - &worker_data); // Opaque data for calibration worked - } - - // Calculate calibration values for each mag - - float sphere_x[max_mags]; - float sphere_y[max_mags]; - float sphere_z[max_mags]; - float sphere_radius[max_mags]; - - // Sphere fit the data to get calibration values - if (result == calibrate_return_ok) { - for (unsigned cur_mag=0; cur_magsendMavCommand(_vehicle->defaultComponentId(), - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS, - true, /* showErrors */ - sensorId, -sphere_x[cur_mag], -sphere_y[cur_mag], -sphere_z[cur_mag]); - } - } - } - } - - return result; -} - -CalWorkerThread::calibrate_return CalWorkerThread::mag_calibration_worker(detect_orientation_return orientation, void* data) -{ - calibrate_return result = calibrate_return_ok; - - unsigned int calibration_counter_side; - - mag_worker_data_t* worker_data = (mag_worker_data_t*)(data); - - _emitVehicleTextMessage(QStringLiteral("[cal] Rotate vehicle around the detected orientation")); - _emitVehicleTextMessage(QStringLiteral("[cal] Continue rotation for %1 seconds").arg(worker_data->calibration_interval_perside_seconds)); - - uint64_t calibration_deadline = QGC::groundTimeUsecs() + worker_data->calibration_interval_perside_useconds; - - unsigned int loop_interval_usecs = (worker_data->calibration_interval_perside_seconds * 1000000) / worker_data->calibration_points_perside; - - calibration_counter_side = 0; - - while (QGC::groundTimeUsecs() < calibration_deadline && calibration_counter_side < worker_data->calibration_points_perside) { - if (_cancel) { - result = calibrate_return_cancelled; - break; - } - - for (size_t cur_mag=0; cur_magx[cur_mag][worker_data->calibration_counter_total[cur_mag]] = copyLastScaledImu.xmag; - worker_data->y[cur_mag][worker_data->calibration_counter_total[cur_mag]] = copyLastScaledImu.ymag; - worker_data->z[cur_mag][worker_data->calibration_counter_total[cur_mag]] = copyLastScaledImu.zmag; - worker_data->calibration_counter_total[cur_mag]++; - } - - calibration_counter_side++; - - // Progress indicator for side - _emitVehicleTextMessage(QStringLiteral("[cal] %1 side calibration: progress <%2>").arg(detect_orientation_str(orientation)).arg(progress_percentage(worker_data) + - (unsigned)((100 / calibration_sides) * ((float)calibration_counter_side / (float)worker_data->calibration_points_perside)))); - - usleep(loop_interval_usecs); - } - - if (result == calibrate_return_ok) { - _emitVehicleTextMessage(QStringLiteral("[cal] %1 side done, rotate to a different side").arg(detect_orientation_str(orientation))); - - worker_data->done_count++; - _emitVehicleTextMessage(QStringLiteral("[cal] progress <%1>").arg(progress_percentage(worker_data))); - } - - return result; -} - -CalWorkerThread::calibrate_return CalWorkerThread::calibrate_from_orientation( - bool side_data_collected[detect_orientation_side_count], - void* worker_data) -{ - calibrate_return result = calibrate_return_ok; - - unsigned orientation_failures = 0; - - // Rotate through all requested orientations - while (true) { - if (_cancel) { - result = calibrate_return_cancelled; - break; - } - - unsigned int side_complete_count = 0; - - // Update the number of completed sides - for (unsigned i = 0; i < detect_orientation_side_count; i++) { - if (side_data_collected[i]) { - side_complete_count++; - } - } - - if (side_complete_count == detect_orientation_side_count) { - // We have completed all sides, move on - break; - } - - /* inform user which orientations are still needed */ - char pendingStr[256]; - pendingStr[0] = 0; - - for (unsigned int cur_orientation=0; cur_orientation 1000) { - break; - } - } else { - stillDetectTime = QGC::groundTimeMilliseconds(); - stillDetected = true; - } - } else { - stillDetected = false; - } - - if (_cancel) { - break; - } - - // FIXME: No timeout for never detect still - - usleep(1000); - } - - static const uint16_t rawImuOneG = 800; - static const uint16_t rawImuNoGThreshold = 200; - - if (lastX > rawImuOneG && abs(lastY) < rawImuNoGThreshold && abs(lastZ) < rawImuNoGThreshold) { - return DETECT_ORIENTATION_TAIL_DOWN; // [ g, 0, 0 ] - } - - if (lastX < -rawImuOneG && abs(lastY) < rawImuNoGThreshold && abs(lastZ) < rawImuNoGThreshold) { - return DETECT_ORIENTATION_NOSE_DOWN; // [ -g, 0, 0 ] - } - - if (lastY > rawImuOneG && abs(lastX) < rawImuNoGThreshold && abs(lastZ) < rawImuNoGThreshold) { - return DETECT_ORIENTATION_LEFT; // [ 0, g, 0 ] - } - - if (lastY < -rawImuOneG && abs(lastX) < rawImuNoGThreshold && abs(lastZ) < rawImuNoGThreshold) { - return DETECT_ORIENTATION_RIGHT; // [ 0, -g, 0 ] - } - - if (lastZ > rawImuOneG && abs(lastX) < rawImuNoGThreshold && abs(lastY) < rawImuNoGThreshold) { - return DETECT_ORIENTATION_UPSIDE_DOWN; // [ 0, 0, g ] - } - - if (lastZ < -rawImuOneG && abs(lastX) < rawImuNoGThreshold && abs(lastY) < rawImuNoGThreshold) { - return DETECT_ORIENTATION_RIGHTSIDE_UP; // [ 0, 0, -g ] - } - - _emitVehicleTextMessage(QStringLiteral("[cal] ERROR: invalid orientation")); - - return DETECT_ORIENTATION_ERROR; // Can't detect orientation -} - -const char* CalWorkerThread::detect_orientation_str(enum detect_orientation_return orientation) -{ - static const char* rgOrientationStrs[] = { - "back", // tail down - "front", // nose down - "left", - "right", - "up", // upside-down - "down", // right-side up - "error" - }; - - return rgOrientationStrs[orientation]; -} - -int CalWorkerThread::sphere_fit_least_squares(const float x[], const float y[], const float z[], - unsigned int size, unsigned int max_iterations, float delta, float *sphere_x, float *sphere_y, float *sphere_z, - float *sphere_radius) -{ - - float x_sumplain = 0.0f; - float x_sumsq = 0.0f; - float x_sumcube = 0.0f; - - float y_sumplain = 0.0f; - float y_sumsq = 0.0f; - float y_sumcube = 0.0f; - - float z_sumplain = 0.0f; - float z_sumsq = 0.0f; - float z_sumcube = 0.0f; - - float xy_sum = 0.0f; - float xz_sum = 0.0f; - float yz_sum = 0.0f; - - float x2y_sum = 0.0f; - float x2z_sum = 0.0f; - float y2x_sum = 0.0f; - float y2z_sum = 0.0f; - float z2x_sum = 0.0f; - float z2y_sum = 0.0f; - - for (unsigned int i = 0; i < size; i++) { - - float x2 = x[i] * x[i]; - float y2 = y[i] * y[i]; - float z2 = z[i] * z[i]; - - x_sumplain += x[i]; - x_sumsq += x2; - x_sumcube += x2 * x[i]; - - y_sumplain += y[i]; - y_sumsq += y2; - y_sumcube += y2 * y[i]; - - z_sumplain += z[i]; - z_sumsq += z2; - z_sumcube += z2 * z[i]; - - xy_sum += x[i] * y[i]; - xz_sum += x[i] * z[i]; - yz_sum += y[i] * z[i]; - - x2y_sum += x2 * y[i]; - x2z_sum += x2 * z[i]; - - y2x_sum += y2 * x[i]; - y2z_sum += y2 * z[i]; - - z2x_sum += z2 * x[i]; - z2y_sum += z2 * y[i]; - } - - // - //Least Squares Fit a sphere A,B,C with radius squared Rsq to 3D data - // - // P is a structure that has been computed with the data earlier. - // P.npoints is the number of elements; the length of X,Y,Z are identical. - // P's members are logically named. - // - // X[n] is the x component of point n - // Y[n] is the y component of point n - // Z[n] is the z component of point n - // - // A is the x coordiante of the sphere - // B is the y coordiante of the sphere - // C is the z coordiante of the sphere - // Rsq is the radius squared of the sphere. - // - //This method should converge; maybe 5-100 iterations or more. - // - float x_sum = x_sumplain / size; //sum( X[n] ) - float x_sum2 = x_sumsq / size; //sum( X[n]^2 ) - float x_sum3 = x_sumcube / size; //sum( X[n]^3 ) - float y_sum = y_sumplain / size; //sum( Y[n] ) - float y_sum2 = y_sumsq / size; //sum( Y[n]^2 ) - float y_sum3 = y_sumcube / size; //sum( Y[n]^3 ) - float z_sum = z_sumplain / size; //sum( Z[n] ) - float z_sum2 = z_sumsq / size; //sum( Z[n]^2 ) - float z_sum3 = z_sumcube / size; //sum( Z[n]^3 ) - - float XY = xy_sum / size; //sum( X[n] * Y[n] ) - float XZ = xz_sum / size; //sum( X[n] * Z[n] ) - float YZ = yz_sum / size; //sum( Y[n] * Z[n] ) - float X2Y = x2y_sum / size; //sum( X[n]^2 * Y[n] ) - float X2Z = x2z_sum / size; //sum( X[n]^2 * Z[n] ) - float Y2X = y2x_sum / size; //sum( Y[n]^2 * X[n] ) - float Y2Z = y2z_sum / size; //sum( Y[n]^2 * Z[n] ) - float Z2X = z2x_sum / size; //sum( Z[n]^2 * X[n] ) - float Z2Y = z2y_sum / size; //sum( Z[n]^2 * Y[n] ) - - //Reduction of multiplications - float F0 = x_sum2 + y_sum2 + z_sum2; - float F1 = 0.5f * F0; - float F2 = -8.0f * (x_sum3 + Y2X + Z2X); - float F3 = -8.0f * (X2Y + y_sum3 + Z2Y); - float F4 = -8.0f * (X2Z + Y2Z + z_sum3); - - //Set initial conditions: - float A = x_sum; - float B = y_sum; - float C = z_sum; - - //First iteration computation: - float A2 = A * A; - float B2 = B * B; - float C2 = C * C; - float QS = A2 + B2 + C2; - float QB = -2.0f * (A * x_sum + B * y_sum + C * z_sum); - - //Set initial conditions: - float Rsq = F0 + QB + QS; - - //First iteration computation: - float Q0 = 0.5f * (QS - Rsq); - float Q1 = F1 + Q0; - float Q2 = 8.0f * (QS - Rsq + QB + F0); - float aA, aB, aC, nA, nB, nC, dA, dB, dC; - - //Iterate N times, ignore stop condition. - unsigned int n = 0; - -#undef FLT_EPSILON -#define FLT_EPSILON 1.1920929e-07F /* 1E-5 */ - - while (n < max_iterations) { - n++; - - //Compute denominator: - aA = Q2 + 16.0f * (A2 - 2.0f * A * x_sum + x_sum2); - aB = Q2 + 16.0f * (B2 - 2.0f * B * y_sum + y_sum2); - aC = Q2 + 16.0f * (C2 - 2.0f * C * z_sum + z_sum2); - aA = (fabsf(aA) < FLT_EPSILON) ? 1.0f : aA; - aB = (fabsf(aB) < FLT_EPSILON) ? 1.0f : aB; - aC = (fabsf(aC) < FLT_EPSILON) ? 1.0f : aC; - - //Compute next iteration - nA = A - ((F2 + 16.0f * (B * XY + C * XZ + x_sum * (-A2 - Q0) + A * (x_sum2 + Q1 - C * z_sum - B * y_sum))) / aA); - nB = B - ((F3 + 16.0f * (A * XY + C * YZ + y_sum * (-B2 - Q0) + B * (y_sum2 + Q1 - A * x_sum - C * z_sum))) / aB); - nC = C - ((F4 + 16.0f * (A * XZ + B * YZ + z_sum * (-C2 - Q0) + C * (z_sum2 + Q1 - A * x_sum - B * y_sum))) / aC); - - //Check for stop condition - dA = (nA - A); - dB = (nB - B); - dC = (nC - C); - - if ((dA * dA + dB * dB + dC * dC) <= delta) { break; } - - //Compute next iteration's values - A = nA; - B = nB; - C = nC; - A2 = A * A; - B2 = B * B; - C2 = C * C; - QS = A2 + B2 + C2; - QB = -2.0f * (A * x_sum + B * y_sum + C * z_sum); - Rsq = F0 + QB + QS; - Q0 = 0.5f * (QS - Rsq); - Q1 = F1 + Q0; - Q2 = 8.0f * (QS - Rsq + QB + F0); - } - - *sphere_x = A; - *sphere_y = B; - *sphere_z = C; - *sphere_radius = sqrtf(Rsq); - - return 0; -} - -APMCompassCal::APMCompassCal(void) - : _vehicle(nullptr) - , _calWorkerThread(nullptr) -{ - -} - -APMCompassCal::~APMCompassCal() -{ - if (_calWorkerThread) { - _calWorkerThread->terminate(); - // deleteLater so it happens on correct thread - _calWorkerThread->deleteLater(); - } -} - -void APMCompassCal::setVehicle(Vehicle* vehicle) -{ - if (!vehicle) { - qWarning() << "vehicle == NULL"; - } - - _vehicle = vehicle; -} - -void APMCompassCal::startCalibration(void) -{ - _setSensorTransmissionSpeed(true /* fast */); - connect (_vehicle, &Vehicle::mavlinkRawImu, this, &APMCompassCal::_handleMavlinkRawImu); - connect (_vehicle, &Vehicle::mavlinkScaledImu2, this, &APMCompassCal::_handleMavlinkScaledImu2); - connect (_vehicle, &Vehicle::mavlinkScaledImu3, this, &APMCompassCal::_handleMavlinkScaledImu3); - - // Simulate a start message - _emitVehicleTextMessage(QStringLiteral("[cal] calibration started: mag")); - - _calWorkerThread = new CalWorkerThread(_vehicle); - connect(_calWorkerThread, &CalWorkerThread::vehicleTextMessage, this, &APMCompassCal::vehicleTextMessage); - - // Clear the offset parameters so we get raw data - for (int i=0; i<3; i++) { - _calWorkerThread->rgCompassAvailable[i] = true; - - const char* deviceIdParam = CalWorkerThread::rgCompassParams[i][3]; - if (_vehicle->parameterManager()->parameterExists(-1, deviceIdParam)) { - _calWorkerThread->rgCompassAvailable[i] = _vehicle->parameterManager()->getParameter(-1, deviceIdParam)->rawValue().toInt() > 0; - for (int j=0; j<3; j++) { - const char* offsetParam = CalWorkerThread::rgCompassParams[i][j]; - Fact* paramFact = _vehicle->parameterManager()->getParameter(-1, offsetParam); - - _rgSavedCompassOffsets[i][j] = paramFact->rawValue().toFloat(); - paramFact->setRawValue(0.0); - } - } else { - _calWorkerThread->rgCompassAvailable[i] = false; - } - qCDebug(APMCompassCalLog) << QStringLiteral("Compass %1 available: %2").arg(i).arg(_calWorkerThread->rgCompassAvailable[i]); - } - - _calWorkerThread->start(); -} - -void APMCompassCal::cancelCalibration(void) -{ - _stopCalibration(); - - // Put the original offsets back - for (int i=0; i<3; i++) { - for (int j=0; j<3; j++) { - const char* offsetParam = CalWorkerThread::rgCompassParams[i][j]; - if (_vehicle->parameterManager()->parameterExists(-1, offsetParam)) { - _vehicle->parameterManager()->getParameter(-1, offsetParam)-> setRawValue(_rgSavedCompassOffsets[i][j]); - } - } - } - - // Simulate a cancelled message - _emitVehicleTextMessage(QStringLiteral("[cal] calibration cancelled")); -} - -void APMCompassCal::_handleMavlinkRawImu(mavlink_message_t message) -{ - _calWorkerThread->lastScaledImuMutex.lock(); - mavlink_msg_raw_imu_decode(&message, &_calWorkerThread->lastRawImu); - _calWorkerThread->rgLastScaledImu[0].xacc = _calWorkerThread->lastRawImu.xacc; - _calWorkerThread->rgLastScaledImu[0].yacc = _calWorkerThread->lastRawImu.yacc; - _calWorkerThread->rgLastScaledImu[0].zacc = _calWorkerThread->lastRawImu.zacc; - _calWorkerThread->rgLastScaledImu[0].xgyro = _calWorkerThread->lastRawImu.xgyro; - _calWorkerThread->rgLastScaledImu[0].ygyro = _calWorkerThread->lastRawImu.ygyro; - _calWorkerThread->rgLastScaledImu[0].zgyro = _calWorkerThread->lastRawImu.zgyro; - _calWorkerThread->rgLastScaledImu[0].xmag = _calWorkerThread->lastRawImu.xmag; - _calWorkerThread->rgLastScaledImu[0].ymag = _calWorkerThread->lastRawImu.ymag; - _calWorkerThread->rgLastScaledImu[0].zmag = _calWorkerThread->lastRawImu.zmag; - _calWorkerThread->lastScaledImuMutex.unlock(); -} - -void APMCompassCal::_handleMavlinkScaledImu2(mavlink_message_t message) -{ - _calWorkerThread->lastScaledImuMutex.lock(); - mavlink_msg_scaled_imu2_decode(&message, (mavlink_scaled_imu2_t*)&_calWorkerThread->rgLastScaledImu[1]); - _calWorkerThread->lastScaledImuMutex.unlock(); -} - -void APMCompassCal::_handleMavlinkScaledImu3(mavlink_message_t message) -{ - _calWorkerThread->lastScaledImuMutex.lock(); - mavlink_msg_scaled_imu3_decode(&message, (mavlink_scaled_imu3_t*)&_calWorkerThread->rgLastScaledImu[2]); - _calWorkerThread->lastScaledImuMutex.unlock(); -} - -void APMCompassCal::_setSensorTransmissionSpeed(bool fast) -{ - _vehicle->requestDataStream(MAV_DATA_STREAM_RAW_SENSORS, fast ? 10 : 2); -} - -void APMCompassCal::_stopCalibration(void) -{ - _calWorkerThread->cancel(); - disconnect (_vehicle, &Vehicle::mavlinkRawImu, this, &APMCompassCal::_handleMavlinkRawImu); - disconnect (_vehicle, &Vehicle::mavlinkScaledImu2, this, &APMCompassCal::_handleMavlinkScaledImu2); - disconnect (_vehicle, &Vehicle::mavlinkScaledImu3, this, &APMCompassCal::_handleMavlinkScaledImu3); - _setSensorTransmissionSpeed(false /* fast */); -} - -void APMCompassCal::_emitVehicleTextMessage(const QString& message) -{ - qCDebug(APMCompassCalLog()) << message; - emit vehicleTextMessage(_vehicle->id(), 0, MAV_SEVERITY_INFO, message); -} diff --git a/src/AutoPilotPlugins/APM/APMCompassCal.h b/src/AutoPilotPlugins/APM/APMCompassCal.h deleted file mode 100644 index 890719f3f6a..00000000000 --- a/src/AutoPilotPlugins/APM/APMCompassCal.h +++ /dev/null @@ -1,168 +0,0 @@ -/**************************************************************************** - * - * (c) 2009-2020 QGROUNDCONTROL PROJECT - * - * QGroundControl is licensed according to the terms in the file - * COPYING.md in the root of the source code directory. - * - ****************************************************************************/ - - -#ifndef APMCompassCal_H -#define APMCompassCal_H - -#include -#include -#include - -#include "QGCLoggingCategory.h" -#include "QGCMAVLink.h" -#include "Vehicle.h" - -Q_DECLARE_LOGGING_CATEGORY(APMCompassCalLog) - -class CalWorkerThread : public QThread -{ - Q_OBJECT - -public: - CalWorkerThread(Vehicle* vehicle, QObject* parent = nullptr); - - // Cancel currently in progress calibration - void cancel(void) { _cancel = true; } - - // Overrides from QThread - void run(void) Q_DECL_FINAL; - - static const unsigned max_mags = 3; - - bool rgCompassAvailable[max_mags]; - QMutex lastScaledImuMutex; - mavlink_raw_imu_t lastRawImu; - mavlink_scaled_imu_t rgLastScaledImu[max_mags]; - - static const char* rgCompassParams[3][4]; - -signals: - void vehicleTextMessage(int vehicleId, int compId, int severity, QString text); - -private: - void _emitVehicleTextMessage(const QString& message); - - // The routines below are based on the PX4 flight stack compass cal routines. Hence - // the PX4 Flight Stack coding style to maintain some level of code movement. - - static const float mag_sphere_radius; - static const unsigned int calibration_sides; ///< The total number of sides - static const unsigned int calibration_total_points; ///< The total points per magnetometer - static const unsigned int calibraton_duration_seconds; ///< The total duration the routine is allowed to take - - // The order of these cannot change since the calibration calculations depend on them in this order - enum detect_orientation_return { - DETECT_ORIENTATION_TAIL_DOWN, - DETECT_ORIENTATION_NOSE_DOWN, - DETECT_ORIENTATION_LEFT, - DETECT_ORIENTATION_RIGHT, - DETECT_ORIENTATION_UPSIDE_DOWN, - DETECT_ORIENTATION_RIGHTSIDE_UP, - DETECT_ORIENTATION_ERROR - }; - static const unsigned detect_orientation_side_count = 6; - - // Data passed to calibration worker routine - typedef struct { - unsigned done_count; - unsigned int calibration_points_perside; - unsigned int calibration_interval_perside_seconds; - uint64_t calibration_interval_perside_useconds; - unsigned int calibration_counter_total[max_mags]; - bool side_data_collected[detect_orientation_side_count]; - float* x[max_mags]; - float* y[max_mags]; - float* z[max_mags]; - } mag_worker_data_t; - - enum calibrate_return { - calibrate_return_ok, - calibrate_return_error, - calibrate_return_cancelled - }; - - /** - * Least-squares fit of a sphere to a set of points. - * - * Fits a sphere to a set of points on the sphere surface. - * - * @param x point coordinates on the X axis - * @param y point coordinates on the Y axis - * @param z point coordinates on the Z axis - * @param size number of points - * @param max_iterations abort if maximum number of iterations have been reached. If unsure, set to 100. - * @param delta abort if error is below delta. If unsure, set to 0 to run max_iterations times. - * @param sphere_x coordinate of the sphere center on the X axis - * @param sphere_y coordinate of the sphere center on the Y axis - * @param sphere_z coordinate of the sphere center on the Z axis - * @param sphere_radius sphere radius - * - * @return 0 on success, 1 on failure - */ - int sphere_fit_least_squares(const float x[], const float y[], const float z[], - unsigned int size, unsigned int max_iterations, float delta, float *sphere_x, float *sphere_y, float *sphere_z, - float *sphere_radius); - - /// Wait for vehicle to become still and detect it's orientation - /// @return Returns detect_orientation_return according to orientation of still vehicle - enum detect_orientation_return detect_orientation(void); - - /// Returns the human readable string representation of the orientation - /// @param orientation Orientation to return string for, "error" if buffer is too small - const char* detect_orientation_str(enum detect_orientation_return orientation); - - /// Perform calibration sequence which require a rest orientation detection prior to calibration. - /// @return OK: Calibration succeeded, ERROR: Calibration failed - calibrate_return calibrate_from_orientation( - bool side_data_collected[detect_orientation_side_count], ///< Sides for which data still needs calibration - void* worker_data); ///< Opaque data passed to worker routine - - calibrate_return calibrate(void); - calibrate_return mag_calibration_worker(detect_orientation_return orientation, void* data); - unsigned progress_percentage(mag_worker_data_t* worker_data); - - Vehicle* _vehicle; - bool _cancel; -}; - -// Used to calibrate APM Stack compass by simulating PX4 Flight Stack firmware compass cal -// on the ground station side of things. -class APMCompassCal : public QObject -{ - Q_OBJECT - -public: - APMCompassCal(void); - ~APMCompassCal(); - - void setVehicle(Vehicle* vehicle); - void startCalibration(void); - void cancelCalibration(void); - -signals: - void vehicleTextMessage(int vehicleId, int compId, int severity, QString text); - -private slots: - void _handleMavlinkRawImu(mavlink_message_t message); - void _handleMavlinkScaledImu2(mavlink_message_t message); - void _handleMavlinkScaledImu3(mavlink_message_t message); - -private: - void _setSensorTransmissionSpeed(bool fast); - void _stopCalibration(void); - void _emitVehicleTextMessage(const QString& message); - - Vehicle* _vehicle; - CalWorkerThread* _calWorkerThread; - float _rgSavedCompassOffsets[3][3]; -}; - -#endif - diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml index c125e8de9a0..b032bca7b02 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml +++ b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml @@ -168,9 +168,6 @@ SetupPage { onCalibrationComplete: { switch (calType) { case APMSensorsComponentController.CalTypeAccel: - case APMSensorsComponentController.CalTypeOffboardCompass: - postCalibrationComponent.createObject(mainWindow).open() - break case APMSensorsComponentController.CalTypeOnboardCompass: _singleCompassSettingsComponentShowPriority = true postOnboardCompassCalibrationComponent.createObject(mainWindow).open() diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc index fbd53d05bfc..944843a2ccf 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc @@ -58,9 +58,6 @@ APMSensorsComponentController::APMSensorsComponentController(void) , _waitingForCancel(false) , _restoreCompassCalFitness(false) { - _compassCal.setVehicle(_vehicle); - connect(&_compassCal, &APMCompassCal::vehicleTextMessage, this, &APMSensorsComponentController::_handleUASTextMessage); - APMAutoPilotPlugin * apmPlugin = qobject_cast(_vehicle->autopilotPlugin()); // Find the sensors component @@ -274,9 +271,6 @@ void APMSensorsComponentController::_mavCommandResult(int vehicleId, int compone 0, // no delayed start 0); // no auto-reboot - } else { - // Onboard mag cal is not supported - _compassCal.startCalibration(); } } else if (command == MAV_CMD_DO_START_MAG_CAL && result != MAV_RESULT_ACCEPTED) { _restorePreviousCompassCalFitness(); @@ -452,11 +446,7 @@ void APMSensorsComponentController::cancelCalibration(void) { _cancelButton->setEnabled(false); - if (_calTypeInProgress == CalTypeOffboardCompass) { - _waitingForCancel = true; - emit waitingForCancelChanged(); - _compassCal.cancelCalibration(); - } else if (_calTypeInProgress == CalTypeOnboardCompass) { + if (_calTypeInProgress == CalTypeOnboardCompass) { _vehicle->sendMavCommand(_vehicle->defaultComponentId(), MAV_CMD_DO_CANCEL_MAG_CAL, true /* showError */); _stopCalibration(StopCalibrationCancelled); } else { diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.h b/src/AutoPilotPlugins/APM/APMSensorsComponentController.h index 2fe31a969d4..bca5fc4877a 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.h +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.h @@ -15,7 +15,6 @@ #include "FactPanelController.h" #include "QGCLoggingCategory.h" #include "APMSensorsComponent.h" -#include "APMCompassCal.h" Q_DECLARE_LOGGING_CATEGORY(APMSensorsComponentControllerLog) Q_DECLARE_LOGGING_CATEGORY(APMSensorsComponentControllerVerboseLog) @@ -97,7 +96,6 @@ class APMSensorsComponentController : public FactPanelController CalTypeAccel, CalTypeGyro, CalTypeOnboardCompass, - CalTypeOffboardCompass, CalTypeLevelHorizon, CalTypeCompassMot, CalTypePressure, @@ -161,7 +159,6 @@ private slots: void _updateAndEmitShowOrientationCalArea(bool show); - APMCompassCal _compassCal; APMSensorsComponent* _sensorsComponent; QQuickItem* _statusLog; diff --git a/src/AutoPilotPlugins/CMakeLists.txt b/src/AutoPilotPlugins/CMakeLists.txt index 5331d61ec78..ab812c20a60 100644 --- a/src/AutoPilotPlugins/CMakeLists.txt +++ b/src/AutoPilotPlugins/CMakeLists.txt @@ -8,7 +8,6 @@ add_library(AutoPilotPlugins APM/APMAirframeComponentController.cc APM/APMAutoPilotPlugin.cc APM/APMCameraComponent.cc - APM/APMCompassCal.cc APM/APMFlightModesComponent.cc APM/APMFlightModesComponentController.cc APM/APMFollowComponent.cc From f868d87069e24d49487b76bb35259b7a4c457ed5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 24 Oct 2023 20:19:21 +1100 Subject: [PATCH 083/118] qgroundcotrol.pro: do not build removed APMCompassCal --- qgroundcontrol.pro | 2 -- 1 file changed, 2 deletions(-) diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 4f9ca79142e..5de21a05c3a 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -1138,7 +1138,6 @@ APMFirmwarePlugin { src/AutoPilotPlugins/APM/APMAirframeComponentController.h \ src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h \ src/AutoPilotPlugins/APM/APMCameraComponent.h \ - src/AutoPilotPlugins/APM/APMCompassCal.h \ src/AutoPilotPlugins/APM/APMFlightModesComponent.h \ src/AutoPilotPlugins/APM/APMFlightModesComponentController.h \ src/AutoPilotPlugins/APM/APMFollowComponent.h \ @@ -1167,7 +1166,6 @@ APMFirmwarePlugin { src/AutoPilotPlugins/APM/APMAirframeComponentController.cc \ src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc \ src/AutoPilotPlugins/APM/APMCameraComponent.cc \ - src/AutoPilotPlugins/APM/APMCompassCal.cc \ src/AutoPilotPlugins/APM/APMFlightModesComponent.cc \ src/AutoPilotPlugins/APM/APMFlightModesComponentController.cc \ src/AutoPilotPlugins/APM/APMFollowComponent.cc \ From 10394d60a9ad85fb01cc0104682b5ac71457fdee Mon Sep 17 00:00:00 2001 From: Hamza ZOGHMAR Date: Thu, 26 Oct 2023 16:36:35 +0200 Subject: [PATCH 084/118] QGCTextField: fix forcing the use of virtual numeric keyboard --- src/QmlControls/QGCTextField.qml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/QmlControls/QGCTextField.qml b/src/QmlControls/QGCTextField.qml index 560cf8fd014..89934a177f9 100644 --- a/src/QmlControls/QGCTextField.qml +++ b/src/QmlControls/QGCTextField.qml @@ -13,8 +13,8 @@ TextField { activeFocusOnPress: true antialiasing: true inputMethodHints: numericValuesOnly && !ScreenTools.isiOS ? - Qt.ImhNone : // iOS numeric keyboard has no done button, we can't use it. - Qt.ImhFormattedNumbersOnly // Forces use of virtual numeric keyboard instead of full keyboard + Qt.ImhFormattedNumbersOnly: // Forces use of virtual numeric keyboard instead of full keyboard + Qt.ImhNone // iOS numeric keyboard has no done button, we can't use it. property bool showUnits: false property bool showHelp: false From d56cdb90e767a99605b13b2bed1957c1c60e7609 Mon Sep 17 00:00:00 2001 From: James Mare Date: Thu, 14 Sep 2023 09:26:18 +1000 Subject: [PATCH 085/118] FlyView: add a toolinset viewer in the fly view this is disabled by default but can be manually uncommented in the flyview to test or debug tool insets --- qgroundcontrol.qrc | 7 +- src/FlightDisplay/FlyView.qml | 15 ++ src/FlightDisplay/FlyViewInsetViewer.qml | 194 ++++++++++++++++++ .../QGroundControl/FlightDisplay/qmldir | 1 + 4 files changed, 213 insertions(+), 4 deletions(-) create mode 100644 src/FlightDisplay/FlyViewInsetViewer.qml diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index f07d6a356e5..5877af05917 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -185,7 +185,7 @@ src/PlanView/TerrainStatus.qml src/PlanView/TakeoffItemMapVisual.qml src/QmlControls/ToolStrip.qml - src/QmlControls/ToolStripHoverButton.qml + src/QmlControls/ToolStripHoverButton.qml src/PlanView/TransectStyleComplexItemEditor.qml src/PlanView/TransectStyleComplexItemStats.qml src/PlanView/TransectStyleComplexItemTabBar.qml @@ -287,6 +287,8 @@ src/AnalyzeView/VibrationPage.qml src/FlightDisplay/VirtualJoystick.qml src/PlanView/VTOLLandingPatternEditor.qml + src/comm/MockLinkOptionsDlg.qml + src/FlightDisplay/FlyViewInsetViewer.qml src/FirstRunPromptDialogs/UnitsFirstRunPrompt.qml @@ -357,7 +359,4 @@ src/comm/MockLink.Parameter.MetaData.json src/comm/Mocklink.Arduplane.params.ftp.bin - - src/comm/MockLinkOptionsDlg.qml - diff --git a/src/FlightDisplay/FlyView.qml b/src/FlightDisplay/FlyView.qml index 0f0a378bc6b..68c2a8b2af6 100644 --- a/src/FlightDisplay/FlyView.qml +++ b/src/FlightDisplay/FlyView.qml @@ -85,6 +85,7 @@ Item { visible: !QGroundControl.videoManager.fullScreen } + FlyViewCustomLayer { id: customOverlay anchors.fill: widgetLayer @@ -94,6 +95,20 @@ Item { visible: !QGroundControl.videoManager.fullScreen } + // Development tool for visualizing the insets for a paticular layer, enable if needed + /* + FlyViewInsetViewer { + id: widgetLayerInsetViewer + anchors.top: parent.top + anchors.bottom: parent.bottom + anchors.left: parent.left + anchors.right: guidedValueSlider.visible ? guidedValueSlider.left : parent.right + + z: widgetLayer.z + 1 + + insetsToView: customOverlay.totalToolInsets + }*/ + GuidedActionsController { id: guidedActionsController missionController: _missionController diff --git a/src/FlightDisplay/FlyViewInsetViewer.qml b/src/FlightDisplay/FlyViewInsetViewer.qml new file mode 100644 index 00000000000..2f95208ffeb --- /dev/null +++ b/src/FlightDisplay/FlyViewInsetViewer.qml @@ -0,0 +1,194 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +import QtQuick 2.12 +import QtQuick.Controls 2.4 +import QtQuick.Dialogs 1.3 +import QtQuick.Layouts 1.12 + +import QtLocation 5.3 +import QtPositioning 5.3 +import QtQuick.Window 2.2 +import QtQml.Models 2.1 + +import QGroundControl 1.0 +import QGroundControl.Controls 1.0 +import QGroundControl.Controllers 1.0 +import QGroundControl.FlightDisplay 1.0 +import QGroundControl.ScreenTools 1.0 +import QGroundControl.FlightMap 1.0 + + +// This is the ui overlay layer for the widgets/tools for Fly View +Item { + id: _root + property var insetsToView: QGCToolInsets {} + property int _linethickness: 3 + + Rectangle { + anchors.left: parent.left + anchors.verticalCenter: parent.verticalCenter + anchors.leftMargin: parent.width/8 + height: checkboxcolumn.height + width: checkboxcolumn.width + color: "dimgray" + + ColumnLayout { + id: checkboxcolumn + QGCCheckBox{ + checked: true + text: "leftEdgeTopInset" + onClicked: leftEdgeTopInset.visible = checked + textColor: leftEdgeTopInset.color + textBold: true + } + QGCCheckBox{ + checked: true + text: "leftEdgeBottomInset" + onClicked: leftEdgeBottomInset.visible = checked + textColor: leftEdgeBottomInset.color + textBold: true + } + QGCCheckBox{ + checked: true + text: "rightEdgeTopInset" + onClicked: rightEdgeTopInset.visible = checked + textColor: rightEdgeTopInset.color + textBold: true + } + QGCCheckBox{ + checked: true + text: "rightEdgeBottomInset" + onClicked: rightEdgeBottomInset.visible = checked + textColor: rightEdgeBottomInset.color + textBold: true + } + QGCCheckBox{ + checked: true + text: "topEdgeLeftInset" + onClicked: topEdgeLeftInset.visible = checked + textColor: topEdgeLeftInset.color + textBold: true + } + QGCCheckBox{ + checked: true + text: "topEdgeRightInset" + onClicked: topEdgeRightInset.visible = checked + textColor: topEdgeRightInset.color + textBold: true + } + QGCCheckBox{ + checked: true + text: "bottomEdgeLeftInset" + onClicked: bottomEdgeLeftInset.visible = checked + textColor: bottomEdgeLeftInset.color + textBold: true + } + QGCCheckBox{ + checked: true + text: "bottomEdgeRightInset" + onClicked: bottomEdgeRightInset.visible = checked + textColor: bottomEdgeRightInset.color + textBold: true + } + QGCCheckBox{ + checked: true + text: "centerInsetRect" + onClicked: centerInsetRect.visible = checked + textColor: centerInsetRect.border.color + textBold: true + } + } + + } + + Rectangle { // leftEdgeTopInset + id: leftEdgeTopInset + anchors.top: parent.top + anchors.left: parent.left + anchors.leftMargin: insetsToView.leftEdgeTopInset + height: parent.height + width: _linethickness + color: "coral" + } + Rectangle { // leftEdgeBottomInset + id: leftEdgeBottomInset + anchors.top: parent.top + anchors.left: parent.left + anchors.leftMargin: insetsToView.leftEdgeBottomInset + height: parent.height + width: _linethickness + color: "cornflowerblue" + } + Rectangle { // rightEdgeTopInset + id: rightEdgeTopInset + anchors.top: parent.top + anchors.right: parent.right + anchors.rightMargin: insetsToView.rightEdgeTopInset + height: parent.height + width: _linethickness + color: "darkslateblue" + } + Rectangle { // rightEdgeBottomInset + id: rightEdgeBottomInset + anchors.top: parent.top + anchors.right: parent.right + anchors.rightMargin: insetsToView.rightEdgeBottomInset + height: parent.height + width: _linethickness + color: "firebrick" + } + Rectangle { // topEdgeLeftInset + id: topEdgeLeftInset + anchors.top: parent.top + anchors.left: parent.left + anchors.topMargin: insetsToView.topEdgeLeftInset + height: _linethickness + width: parent.width + color: "mediumseagreen" + } + Rectangle { // topEdgeRightInset + id: topEdgeRightInset + anchors.top: parent.top + anchors.left: parent.left + anchors.topMargin: insetsToView.topEdgeRightInset + height: _linethickness + width: parent.width + color: "moccasin" + } + Rectangle { // bottomEdgeLeftInset + id: bottomEdgeLeftInset + anchors.bottom: parent.bottom + anchors.left: parent.left + anchors.bottomMargin: insetsToView.bottomEdgeLeftInset + height: _linethickness + width: parent.width + color: "salmon" + } + Rectangle { // bottomEdgeRightInset + id: bottomEdgeRightInset + anchors.bottom: parent.bottom + anchors.left: parent.left + anchors.bottomMargin: insetsToView.bottomEdgeRightInset + height: _linethickness + width: parent.width + color: "slategrey" + } + Rectangle { + id: centerInsetRect + x: insetsToView.leftEdgeCenterInset + y: insetsToView.topEdgeCenterInset + width: _root.width - insetsToView.leftEdgeCenterInset - insetsToView.rightEdgeCenterInset + height: _root.height - insetsToView.topEdgeCenterInset - insetsToView.bottomEdgeCenterInset + color: "transparent" + border.color: "yellow" + border.width: 1 + radius: 0 + } +} diff --git a/src/QmlControls/QGroundControl/FlightDisplay/qmldir b/src/QmlControls/QGroundControl/FlightDisplay/qmldir index 4c2ee84ae65..f27005c9413 100644 --- a/src/QmlControls/QGroundControl/FlightDisplay/qmldir +++ b/src/QmlControls/QGroundControl/FlightDisplay/qmldir @@ -11,6 +11,7 @@ FlyViewToolStrip 1.0 FlyViewToolStrip.qml FlyViewToolStripActionList 1.0 FlyViewToolStripActionList.qml FlyViewVideo 1.0 FlyViewVideo.qml FlyViewWidgetLayer 1.0 FlyViewWidgetLayer.qml +FlyViewInsetViewer 1.0 FlyViewInsetViewer.qml GuidedActionActionList 1.0 GuidedActionActionList.qml GuidedActionConfirm 1.0 GuidedActionConfirm.qml GuidedActionsController 1.0 GuidedActionsController.qml From 1b37c0ec46ca8ef4eab3eb9e881970be3241581f Mon Sep 17 00:00:00 2001 From: James Mare Date: Thu, 14 Sep 2023 09:26:39 +1000 Subject: [PATCH 086/118] FlyView: Fix insets on the widget layer makes all elements on the fly view widget layer properly pass out tool insets --- src/FlightDisplay/FlyViewWidgetLayer.qml | 53 ++++++++++++++++++------ 1 file changed, 40 insertions(+), 13 deletions(-) diff --git a/src/FlightDisplay/FlyViewWidgetLayer.qml b/src/FlightDisplay/FlyViewWidgetLayer.qml index cf0df8133b6..04bae6cf620 100644 --- a/src/FlightDisplay/FlyViewWidgetLayer.qml +++ b/src/FlightDisplay/FlyViewWidgetLayer.qml @@ -51,17 +51,17 @@ Item { QGCToolInsets { id: _totalToolInsets leftEdgeTopInset: toolStrip.leftInset - leftEdgeCenterInset: toolStrip.leftInset - leftEdgeBottomInset: parentToolInsets.leftEdgeBottomInset - rightEdgeTopInset: parentToolInsets.rightEdgeTopInset - rightEdgeCenterInset: parentToolInsets.rightEdgeCenterInset - rightEdgeBottomInset: parentToolInsets.rightEdgeBottomInset - topEdgeLeftInset: parentToolInsets.topEdgeLeftInset - topEdgeCenterInset: parentToolInsets.topEdgeCenterInset - topEdgeRightInset: parentToolInsets.topEdgeRightInset - bottomEdgeLeftInset: parentToolInsets.bottomEdgeLeftInset - bottomEdgeCenterInset: mapScale.centerInset - bottomEdgeRightInset: 0 + leftEdgeCenterInset: parentToolInsets.leftEdgeCenterInset + leftEdgeBottomInset: virtualJoystickMultiTouch.visible ? virtualJoystickMultiTouch.leftInset : parentToolInsets.leftEdgeBottomInset + rightEdgeTopInset: instrumentPanel.rightInset + rightEdgeCenterInset: (telemetryPanel.rightInset > photoVideoControl.rightInset) ? telemetryPanel.rightInset : photoVideoControl.rightInset + rightEdgeBottomInset: virtualJoystickMultiTouch.visible ? virtualJoystickMultiTouch.rightInset : parentToolInsets.rightEdgeBottomInset + topEdgeLeftInset: toolStrip.topInset + topEdgeCenterInset: mapScale.topInset + topEdgeRightInset: instrumentPanel.topInset + bottomEdgeLeftInset: virtualJoystickMultiTouch.visible ? virtualJoystickMultiTouch.bottomInset : parentToolInsets.bottomEdgeLeftInset + bottomEdgeCenterInset: telemetryPanel.bottomInset + bottomEdgeRightInset: virtualJoystickMultiTouch.visible ? virtualJoystickMultiTouch.bottomInset : parentToolInsets.bottomEdgeRightInset } FlyViewMissionCompleteDialog { @@ -126,6 +126,7 @@ Item { availableHeight: parent.height - y - _toolsMargin property real rightInset: visible ? parent.width - x : 0 + property real topInset: visible ? y + height : 0 } PhotoVideoControl { @@ -133,6 +134,9 @@ Item { anchors.margins: _toolsMargin anchors.right: parent.right width: _rightPanelWidth + + property real rightInset: visible ? parent.width - x : 0 + state: _verticalCenter ? "verticalCenter" : "topAnchor" states: [ State { @@ -161,6 +165,9 @@ Item { x: recalcXPosition() anchors.margins: _toolsMargin + property real bottomInset: 0 + property real rightInset: 0 + // States for custom layout support states: [ State { @@ -178,6 +185,8 @@ Item { PropertyChanges { target: telemetryPanel x: recalcXPosition() + bottomInset: visible ? parent.height-y : 0 + rightInset: 0 } }, @@ -192,6 +201,11 @@ Item { anchors.right: parent.right anchors.verticalCenter: undefined } + PropertyChanges { + target: telemetryPanel + bottomInset: 0 + rightInset: visible ? parent.width - x : 0 + } }, State { @@ -205,6 +219,11 @@ Item { anchors.right: parent.right anchors.verticalCenter: parent.verticalCenter } + PropertyChanges { + target: telemetryPanel + bottomInset: 0 + rightInset: visible ? parent.width - x : 0 + } } ] @@ -240,6 +259,12 @@ Item { property bool autoCenterThrottle: QGroundControl.settingsManager.appSettings.virtualJoystickAutoCenterThrottle.rawValue property bool _virtualJoystickEnabled: QGroundControl.settingsManager.appSettings.virtualJoystick.rawValue + + property real bottomInset: parent.height-y + + // Width is difficult to access directly hence this hack which may not work in all circumstances + property real leftInset: visible ? bottomInset + width/18 - ScreenTools.defaultFontPixelHeight*2 : 0 + property real rightInset: visible ? bottomInset + width/18 - ScreenTools.defaultFontPixelHeight*2 : 0 } FlyViewToolStrip { @@ -254,7 +279,9 @@ Item { onDisplayPreFlightChecklist: preFlightChecklistPopup.createObject(mainWindow).open() - property real leftInset: x + width + + property real topInset: visible ? y + height : 0 + property real leftInset: visible ? x + width : 0 } GripperMenu { @@ -275,7 +302,7 @@ Item { buttonsOnLeft: false visible: !ScreenTools.isTinyScreen && QGroundControl.corePlugin.options.flyView.showMapScale && mapControl.pipState.state === mapControl.pipState.fullState - property real centerInset: visible ? parent.height - y : 0 + property real topInset: visible ? y + height : 0 } Component { From cf822ad0d29b3e80b08d7de252399760c1ff3829 Mon Sep 17 00:00:00 2001 From: James Mare Date: Tue, 29 Aug 2023 14:46:58 +1000 Subject: [PATCH 087/118] FlyView: Fix tool insets in the custom layer There is a default custom layer which is used in a non-custom build. This commit makes this layer properly pass through the tool insets unchanged --- src/FlightDisplay/FlyViewCustomLayer.qml | 27 ++++++++++++------------ 1 file changed, 14 insertions(+), 13 deletions(-) diff --git a/src/FlightDisplay/FlyViewCustomLayer.qml b/src/FlightDisplay/FlyViewCustomLayer.qml index 423dc2c8000..c09b7e4f843 100644 --- a/src/FlightDisplay/FlyViewCustomLayer.qml +++ b/src/FlightDisplay/FlyViewCustomLayer.qml @@ -36,19 +36,20 @@ Item { property var totalToolInsets: _toolInsets // These are the insets for your custom overlay additions property var mapControl + // since this file is a placeholder for the custom layer in a standard build, we will just pass through the parent insets QGCToolInsets { - id: _toolInsets - leftEdgeCenterInset: 0 - leftEdgeTopInset: 0 - leftEdgeBottomInset: 0 - rightEdgeCenterInset: 0 - rightEdgeTopInset: 0 - rightEdgeBottomInset: 0 - topEdgeCenterInset: 0 - topEdgeLeftInset: 0 - topEdgeRightInset: 0 - bottomEdgeCenterInset: 0 - bottomEdgeLeftInset: 0 - bottomEdgeRightInset: 0 + id: _toolInsets + leftEdgeTopInset: parentToolInsets.leftEdgeTopInset + leftEdgeCenterInset: parentToolInsets.leftEdgeCenterInset + leftEdgeBottomInset: parentToolInsets.leftEdgeBottomInset + rightEdgeTopInset: parentToolInsets.rightEdgeTopInset + rightEdgeCenterInset: parentToolInsets.rightEdgeCenterInset + rightEdgeBottomInset: parentToolInsets.rightEdgeBottomInset + topEdgeLeftInset: parentToolInsets.topEdgeLeftInset + topEdgeCenterInset: parentToolInsets.topEdgeCenterInset + topEdgeRightInset: parentToolInsets.topEdgeRightInset + bottomEdgeLeftInset: parentToolInsets.bottomEdgeLeftInset + bottomEdgeCenterInset: parentToolInsets.bottomEdgeCenterInset + bottomEdgeRightInset: parentToolInsets.bottomEdgeRightInset } } From e6220e011b330becba84cfa42c5fe6f2e894343e Mon Sep 17 00:00:00 2001 From: James Mare Date: Wed, 30 Aug 2023 10:35:20 +1000 Subject: [PATCH 088/118] FlyViewMap: Check corners to recenter the vehicle Previously the FlyViewMap only checked center tool insets to determine whether to recenter the vehicle. This change makes it also check if the vehicle has passed under a corner element using the corner tool insets. This means the view will recenter if the vehicle flys under the instrument panel for example. --- src/FlightDisplay/FlyViewMap.qml | 52 +++++++++++++++++++++++++++++--- 1 file changed, 47 insertions(+), 5 deletions(-) diff --git a/src/FlightDisplay/FlyViewMap.qml b/src/FlightDisplay/FlyViewMap.qml index 4c2b5208a65..1396874846a 100644 --- a/src/FlightDisplay/FlyViewMap.qml +++ b/src/FlightDisplay/FlyViewMap.qml @@ -126,17 +126,59 @@ FlightMap { animateLong.start() } - function _insetRect() { + // returns the rectangle formed by the four center insets + // used for checking if vehicle is under ui, and as a target for recentering the view + function _insetCenterRect() { return Qt.rect(toolInsets.leftEdgeCenterInset, toolInsets.topEdgeCenterInset, _root.width - toolInsets.leftEdgeCenterInset - toolInsets.rightEdgeCenterInset, _root.height - toolInsets.topEdgeCenterInset - toolInsets.bottomEdgeCenterInset) } + // returns the four rectangles formed by the 8 corner insets + // used for detecting if the vehicle has flown under the instrument panel, virtual joystick etc + function _insetCornerRects() { + var rects = { + "topleft": Qt.rect(0,0, + toolInsets.leftEdgeTopInset, + toolInsets.topEdgeLeftInset), + "topright": Qt.rect(_root.width-toolInsets.rightEdgeTopInset,0, + toolInsets.rightEdgeTopInset, + toolInsets.topEdgeRightInset), + "bottomleft": Qt.rect(0,_root.height-toolInsets.bottomEdgeLeftInset, + toolInsets.leftEdgeBottomInset, + toolInsets.bottomEdgeLeftInset), + "bottomright": Qt.rect(_root.width-toolInsets.rightEdgeBottomInset,_root.height-toolInsets.bottomEdgeRightInset, + toolInsets.rightEdgeBottomInset, + toolInsets.bottomEdgeRightInset)} + return rects + } + function recenterNeeded() { var vehiclePoint = _root.fromCoordinate(_activeVehicleCoordinate, false /* clipToViewport */) - var insetRect = _insetRect() - return !pointInRect(vehiclePoint, insetRect) + var centerRect = _insetCenterRect() + //return !pointInRect(vehiclePoint,insetRect) + + // If we are outside the center inset rectangle, recenter + if(!pointInRect(vehiclePoint, centerRect)){ + return true + } + + // if we are inside the center inset rectangle + // then additionally check if we are underneath one of the corner inset rectangles + var cornerRects = _insetCornerRects() + if(pointInRect(vehiclePoint, cornerRects["topleft"])){ + return true + } else if(pointInRect(vehiclePoint, cornerRects["topright"])){ + return true + } else if(pointInRect(vehiclePoint, cornerRects["bottomleft"])){ + return true + } else if(pointInRect(vehiclePoint, cornerRects["bottomright"])){ + return true + } + + // if we are inside the center inset rectangle, and not under any corner elements + return false } function updateMapToVehiclePosition() { @@ -151,8 +193,8 @@ FlightMap { if (firstVehiclePositionReceived && recenterNeeded()) { // Move the map such that the vehicle is centered within the inset area var vehiclePoint = _root.fromCoordinate(_activeVehicleCoordinate, false /* clipToViewport */) - var insetRect = _insetRect() - var centerInsetPoint = Qt.point(insetRect.x + insetRect.width / 2, insetRect.y + insetRect.height / 2) + var centerInsetRect = _insetCenterRect() + var centerInsetPoint = Qt.point(centerInsetRect.x + centerInsetRect.width / 2, centerInsetRect.y + centerInsetRect.height / 2) var centerOffset = Qt.point((_root.width / 2) - centerInsetPoint.x, (_root.height / 2) - centerInsetPoint.y) var vehicleOffsetPoint = Qt.point(vehiclePoint.x + centerOffset.x, vehiclePoint.y + centerOffset.y) var vehicleOffsetCoord = _root.toCoordinate(vehicleOffsetPoint, false /* clipToViewport */) From 376f07b5dbb103c8a28db92038ee5fa62babde63 Mon Sep 17 00:00:00 2001 From: James Mare Date: Tue, 5 Sep 2023 11:14:26 +1000 Subject: [PATCH 089/118] FlyView: Make insets in the widget layer explicit Rename properties to match the inset that they correspond to for better maintainability --- src/FlightDisplay/FlyViewWidgetLayer.qml | 57 ++++++++++++------------ 1 file changed, 29 insertions(+), 28 deletions(-) diff --git a/src/FlightDisplay/FlyViewWidgetLayer.qml b/src/FlightDisplay/FlyViewWidgetLayer.qml index 04bae6cf620..8f4fbea72d2 100644 --- a/src/FlightDisplay/FlyViewWidgetLayer.qml +++ b/src/FlightDisplay/FlyViewWidgetLayer.qml @@ -50,18 +50,18 @@ Item { QGCToolInsets { id: _totalToolInsets - leftEdgeTopInset: toolStrip.leftInset + leftEdgeTopInset: toolStrip.leftEdgeTopInset leftEdgeCenterInset: parentToolInsets.leftEdgeCenterInset - leftEdgeBottomInset: virtualJoystickMultiTouch.visible ? virtualJoystickMultiTouch.leftInset : parentToolInsets.leftEdgeBottomInset - rightEdgeTopInset: instrumentPanel.rightInset - rightEdgeCenterInset: (telemetryPanel.rightInset > photoVideoControl.rightInset) ? telemetryPanel.rightInset : photoVideoControl.rightInset - rightEdgeBottomInset: virtualJoystickMultiTouch.visible ? virtualJoystickMultiTouch.rightInset : parentToolInsets.rightEdgeBottomInset - topEdgeLeftInset: toolStrip.topInset - topEdgeCenterInset: mapScale.topInset - topEdgeRightInset: instrumentPanel.topInset - bottomEdgeLeftInset: virtualJoystickMultiTouch.visible ? virtualJoystickMultiTouch.bottomInset : parentToolInsets.bottomEdgeLeftInset - bottomEdgeCenterInset: telemetryPanel.bottomInset - bottomEdgeRightInset: virtualJoystickMultiTouch.visible ? virtualJoystickMultiTouch.bottomInset : parentToolInsets.bottomEdgeRightInset + leftEdgeBottomInset: virtualJoystickMultiTouch.visible ? virtualJoystickMultiTouch.leftEdgeBottomInset : parentToolInsets.leftEdgeBottomInset + rightEdgeTopInset: instrumentPanel.rightEdgeTopInset + rightEdgeCenterInset: (telemetryPanel.rightEdgeCenterInset > photoVideoControl.rightEdgeCenterInset) ? telemetryPanel.rightEdgeCenterInset : photoVideoControl.rightEdgeCenterInset + rightEdgeBottomInset: virtualJoystickMultiTouch.visible ? virtualJoystickMultiTouch.rightEdgeBottomInset : parentToolInsets.rightEdgeBottomInset + topEdgeLeftInset: toolStrip.topEdgeLeftInset + topEdgeCenterInset: mapScale.topEdgeCenterInset + topEdgeRightInset: instrumentPanel.topEdgeRightInset + bottomEdgeLeftInset: virtualJoystickMultiTouch.visible ? virtualJoystickMultiTouch.bottomEdgeLeftInset : parentToolInsets.bottomEdgeLeftInset + bottomEdgeCenterInset: telemetryPanel.bottomEdgeCenterInset + bottomEdgeRightInset: virtualJoystickMultiTouch.visible ? virtualJoystickMultiTouch.bottomEdgeRightInset : parentToolInsets.bottomEdgeRightInset } FlyViewMissionCompleteDialog { @@ -125,8 +125,8 @@ Item { visible: QGroundControl.corePlugin.options.flyView.showInstrumentPanel && multiVehiclePanelSelector.showSingleVehiclePanel availableHeight: parent.height - y - _toolsMargin - property real rightInset: visible ? parent.width - x : 0 - property real topInset: visible ? y + height : 0 + property real rightEdgeTopInset: visible ? parent.width - x : 0 + property real topEdgeRightInset: visible ? y + height : 0 } PhotoVideoControl { @@ -135,7 +135,7 @@ Item { anchors.right: parent.right width: _rightPanelWidth - property real rightInset: visible ? parent.width - x : 0 + property real rightEdgeCenterInset: visible ? parent.width - x : 0 state: _verticalCenter ? "verticalCenter" : "topAnchor" states: [ @@ -165,8 +165,8 @@ Item { x: recalcXPosition() anchors.margins: _toolsMargin - property real bottomInset: 0 - property real rightInset: 0 + property real bottomEdgeCenterInset: 0 + property real rightEdgeCenterInset: 0 // States for custom layout support states: [ @@ -185,8 +185,8 @@ Item { PropertyChanges { target: telemetryPanel x: recalcXPosition() - bottomInset: visible ? parent.height-y : 0 - rightInset: 0 + bottomEdgeCenterInset: visible ? parent.height-y : 0 + rightEdgeCenterInset: 0 } }, @@ -203,8 +203,8 @@ Item { } PropertyChanges { target: telemetryPanel - bottomInset: 0 - rightInset: visible ? parent.width - x : 0 + bottomEdgeCenterInset: 0 + rightEdgeCenterInset: visible ? parent.width - x : 0 } }, @@ -221,8 +221,8 @@ Item { } PropertyChanges { target: telemetryPanel - bottomInset: 0 - rightInset: visible ? parent.width - x : 0 + bottomEdgeCenterInset: 0 + rightEdgeCenterInset: visible ? parent.width - x : 0 } } ] @@ -260,11 +260,12 @@ Item { property bool _virtualJoystickEnabled: QGroundControl.settingsManager.appSettings.virtualJoystick.rawValue - property real bottomInset: parent.height-y + property real bottomEdgeLeftInset: parent.height-y + property real bottomEdgeRightInset: parent.height-y // Width is difficult to access directly hence this hack which may not work in all circumstances - property real leftInset: visible ? bottomInset + width/18 - ScreenTools.defaultFontPixelHeight*2 : 0 - property real rightInset: visible ? bottomInset + width/18 - ScreenTools.defaultFontPixelHeight*2 : 0 + property real leftEdgeBottomInset: visible ? bottomEdgeLeftInset + width/18 - ScreenTools.defaultFontPixelHeight*2 : 0 + property real rightEdgeBottomInset: visible ? bottomEdgeRightInset + width/18 - ScreenTools.defaultFontPixelHeight*2 : 0 } FlyViewToolStrip { @@ -280,8 +281,8 @@ Item { onDisplayPreFlightChecklist: preFlightChecklistPopup.createObject(mainWindow).open() - property real topInset: visible ? y + height : 0 - property real leftInset: visible ? x + width : 0 + property real topEdgeLeftInset: visible ? y + height : 0 + property real leftEdgeTopInset: visible ? x + width : 0 } GripperMenu { @@ -302,7 +303,7 @@ Item { buttonsOnLeft: false visible: !ScreenTools.isTinyScreen && QGroundControl.corePlugin.options.flyView.showMapScale && mapControl.pipState.state === mapControl.pipState.fullState - property real topInset: visible ? y + height : 0 + property real topEdgeCenterInset: visible ? y + height : 0 } Component { From b2c4f849a0348080868f3e05c1c0888eb3922815 Mon Sep 17 00:00:00 2001 From: James Mare Date: Fri, 8 Sep 2023 14:34:22 +1000 Subject: [PATCH 090/118] custom-example: update qrc files This is an auto update of the custom example qrc files using updateqrc.py --- custom-example/qgcresources.qrc | 7 +++++++ custom-example/qgroundcontrol.qrc | 34 +++++++++++++++++++++++-------- 2 files changed, 33 insertions(+), 8 deletions(-) diff --git a/custom-example/qgcresources.qrc b/custom-example/qgcresources.qrc index c0b4815c56d..3d5fda098ac 100644 --- a/custom-example/qgcresources.qrc +++ b/custom-example/qgcresources.qrc @@ -26,11 +26,15 @@ ../resources/JoystickBezel.png ../resources/JoystickBezelLight.png ../resources/land.svg + ../resources/layout-bottom.svg + ../resources/layout-right.svg ../resources/LockClosed.svg ../resources/LockOpen.svg ../resources/notile.png + ../resources/NoVideoBackground.jpg ../resources/Pause.svg ../resources/pause-mission.svg + ../resources/pencil.svg ../resources/Play.svg ../resources/PowerButton.svg ../resources/QGCLogoBlack.svg @@ -51,6 +55,9 @@ ../resources/XDelete.svg ../resources/XDeleteBlack.svg ../resources/waypoint.svg + ../resources/Gripper.svg + ../resources/GripperRelease.svg + ../resources/GripperGrab.svg ../resources/icons/qgroundcontrol.ico diff --git a/custom-example/qgroundcontrol.qrc b/custom-example/qgroundcontrol.qrc index ed19b5111ee..db956c0d6ff 100644 --- a/custom-example/qgroundcontrol.qrc +++ b/custom-example/qgroundcontrol.qrc @@ -14,9 +14,11 @@ ../src/ui/toolbar/ModeIndicator.qml ../src/ui/toolbar/MultiVehicleSelector.qml ../src/ui/toolbar/RCRSSIIndicator.qml + ../src/ui/toolbar/RemoteIDIndicator.qml ../src/ui/toolbar/ROIIndicator.qml ../src/ui/toolbar/TelemetryRSSIIndicator.qml ../src/ui/toolbar/VTOLModeIndicator.qml + ../src/ui/toolbar/APMSupportForwardingIndicator.qml ../src/FlightDisplay/DefaultChecklist.qml @@ -38,6 +40,7 @@ ../src/ui/preferences/BluetoothSettings.qml ../src/PlanView/CorridorScanEditor.qml ../src/ui/preferences/DebugWindow.qml + ../src/ui/preferences/RemoteIDSettings.qml ../src/AutoPilotPlugins/Common/ESP8266Component.qml ../src/AutoPilotPlugins/Common/ESP8266ComponentSummary.qml ../src/ui/ExitWithErrorWindow.qml @@ -66,6 +69,9 @@ ../src/ui/preferences/MockLink.qml ../src/ui/preferences/MockLinkSettings.qml ../src/AutoPilotPlugins/Common/MotorComponent.qml + ../src/AutoPilotPlugins/PX4/ActuatorComponent.qml + ../src/AutoPilotPlugins/PX4/ActuatorFact.qml + ../src/AutoPilotPlugins/PX4/ActuatorSlider.qml ../src/QtLocationPlugin/QMLControl/OfflineMap.qml ../src/PlanView/PlanToolBar.qml ../src/PlanView/PlanToolBarIndicators.qml @@ -76,6 +82,7 @@ ../src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml ../src/AnalyzeView/AnalyzePage.qml ../src/QmlControls/AppMessages.qml + ../src/QmlControls/AltModeDialog.qml ../src/QmlControls/AxisMonitor.qml ../src/PlanView/CameraCalcCamera.qml ../src/PlanView/CameraCalcGrid.qml @@ -104,6 +111,7 @@ ../src/QmlControls/KMLOrSHPFileDialog.qml ../src/QmlControls/LogReplayStatusBar.qml ../src/ui/toolbar/MainStatusIndicator.qml + ../src/ui/toolbar/FlightModeMenuIndicator.qml ../src/ui/toolbar/MainToolBar.qml ../src/QmlControls/MainWindowSavedState.qml ../src/QmlControls/MAVLinkChart.qml @@ -125,6 +133,7 @@ ../src/QmlControls/PreFlightCheckGroup.qml ../src/QmlControls/PreFlightCheckModel.qml ../src/QmlControls/QGCButton.qml + ../src/QmlControls/QGCColumnButton.qml ../src/QmlControls/AutotuneUI.qml ../src/QmlControls/QGCCheckBox.qml ../src/QmlControls/QGCColoredImage.qml @@ -147,10 +156,10 @@ ../src/QmlControls/QGCMouseArea.qml ../src/QmlControls/QGCMovableItem.qml ../src/QmlControls/QGCPopupDialog.qml - ../src/QmlControls/QGCPopupDialogContainer.qml ../src/QmlControls/QGCPipOverlay.qml ../src/QmlControls/QGCPipState.qml ../src/QmlControls/QGCRadioButton.qml + ../src/QmlControls/QGCSimpleMessageDialog.qml ../src/QmlControls/QGCSlider.qml ../src/QmlControls/QGCSwitch.qml ../src/QmlControls/QGCTabBar.qml @@ -158,9 +167,6 @@ ../src/QmlControls/QGCTextField.qml ../src/QmlControls/QGCToolBarButton.qml ../src/QmlControls/QGCToolInsets.qml - ../src/QmlControls/QGCViewDialog.qml - ../src/QmlControls/QGCViewDialogContainer.qml - ../src/QmlControls/QGCViewMessage.qml ../src/QmlControls/QGroundControl/Controls/qmldir ../src/PlanView/RallyPointEditorHeader.qml ../src/PlanView/RallyPointItemEditor.qml @@ -180,6 +186,7 @@ ../src/PlanView/TakeoffItemMapVisual.qml ../src/QmlControls/ToolStrip.qml ../src/QmlControls/ToolStripHoverButton.qml + ../src/PlanView/TransectStyleComplexItemEditor.qml ../src/PlanView/TransectStyleComplexItemStats.qml ../src/PlanView/TransectStyleComplexItemTabBar.qml ../src/PlanView/TransectStyleComplexItemTerrainFollow.qml @@ -214,9 +221,11 @@ ../src/FlightDisplay/GuidedActionLand.qml ../src/FlightDisplay/GuidedActionList.qml ../src/FlightDisplay/GuidedActionTakeoff.qml + ../src/FlightDisplay/GuidedActionGripper.qml + ../src/FlightDisplay/GripperMenu.qml ../src/FlightDisplay/GuidedActionPause.qml ../src/FlightDisplay/GuidedActionRTL.qml - ../src/FlightDisplay/GuidedAltitudeSlider.qml + ../src/FlightDisplay/GuidedValueSlider.qml ../src/FlightDisplay/GuidedToolStripAction.qml ../src/FlightDisplay/MultiVehicleList.qml ../src/FlightDisplay/PreFlightBatteryCheck.qml @@ -230,6 +239,9 @@ ../src/FlightDisplay/TerrainProgress.qml ../src/FlightDisplay/TelemetryValuesBar.qml ../src/FlightDisplay/VehicleWarnings.qml + ../src/FlightDisplay/ObstacleDistanceOverlay.qml + ../src/FlightDisplay/ObstacleDistanceOverlayMap.qml + ../src/FlightDisplay/ObstacleDistanceOverlayVideo.qml ../src/QmlControls/QGroundControl/FlightDisplay/qmldir ../src/FlightMap/MapItems/CameraTriggerIndicator.qml ../src/FlightMap/Widgets/CenterMapDropButton.qml @@ -274,6 +286,8 @@ ../src/AnalyzeView/VibrationPage.qml ../src/FlightDisplay/VirtualJoystick.qml ../src/PlanView/VTOLLandingPatternEditor.qml + ../src/comm/MockLinkOptionsDlg.qml + ../src/FlightDisplay/FlyViewInsetViewer.qml ../src/FirstRunPromptDialogs/UnitsFirstRunPrompt.qml @@ -290,6 +304,7 @@ ../src/MissionManager/CameraSection.FactMetaData.json ../src/MissionManager/CameraSpec.FactMetaData.json ../src/MissionManager/CorridorScan.SettingsGroup.json + ../src/Settings/RemoteID.SettingsGroup.json ../src/QmlControls/EditPositionDialog.FactMetaData.json ../src/Settings/FirmwareUpgrade.SettingsGroup.json ../src/Settings/FlightMap.SettingsGroup.json @@ -322,13 +337,15 @@ ../src/Vehicle/GPSFact.json ../src/Vehicle/GPSRTKFact.json ../src/Vehicle/SetpointFact.json + ../src/Vehicle/LocalPositionFact.json + ../src/Vehicle/LocalPositionFact.json ../src/Vehicle/SubmarineFact.json ../src/Vehicle/TemperatureFact.json ../src/Vehicle/TerrainFactGroup.json ../src/Vehicle/VehicleFact.json ../src/Vehicle/VibrationFact.json ../src/Vehicle/WindFact.json - ../src/Vehicle/HygrometerFact.json + ../src/Vehicle/HygrometerFact.json ../src/Settings/Video.SettingsGroup.json ../src/MissionManager/VTOLLandingPattern.FactMetaData.json @@ -336,8 +353,9 @@ ../src/comm/APMArduSubMockLink.params ../src/comm/PX4MockLink.params ../src/comm/MockLink.General.MetaData.json - src/comm/MockLink.General.MetaData.json.xz + ../src/comm/MockLink.General.MetaData.json.xz + ../src/comm/MockLink.Parameter.MetaData.json.xz ../src/comm/MockLink.Parameter.MetaData.json - src/comm/MockLink.Parameter.MetaData.json.xz + ../src/comm/Mocklink.Arduplane.params.ftp.bin From 5407ea6f2d2ab87046a3fc1a710d0a5bb1a0a69c Mon Sep 17 00:00:00 2001 From: James Mare Date: Fri, 8 Sep 2023 14:42:04 +1000 Subject: [PATCH 091/118] custom-example: Fix tool insets in flyview Make the custom fly view layer properly inherit so as to pass them through to the map, and also use them to dodge the virtual joysticks. --- custom-example/res/CustomFlyViewOverlay.qml | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/custom-example/res/CustomFlyViewOverlay.qml b/custom-example/res/CustomFlyViewOverlay.qml index 03ff9e8a85e..2015f4ff565 100644 --- a/custom-example/res/CustomFlyViewOverlay.qml +++ b/custom-example/res/CustomFlyViewOverlay.qml @@ -55,8 +55,18 @@ Item { QGCToolInsets { id: _totalToolInsets - topEdgeCenterInset: compassArrowIndicator.y + compassArrowIndicator.height + leftEdgeTopInset: parentToolInsets.leftEdgeTopInset + leftEdgeCenterInset: parentToolInsets.leftEdgeCenterInset + leftEdgeBottomInset: parentToolInsets.leftEdgeBottomInset + rightEdgeTopInset: parentToolInsets.rightEdgeTopInset + rightEdgeCenterInset: parentToolInsets.rightEdgeCenterInset rightEdgeBottomInset: parent.width - compassBackground.x + topEdgeLeftInset: parentToolInsets.topEdgeLeftInset + topEdgeCenterInset: compassArrowIndicator.y + compassArrowIndicator.height + topEdgeRightInset: parentToolInsets.topEdgeRightInset + bottomEdgeLeftInset: parentToolInsets.bottomEdgeLeftInset + bottomEdgeCenterInset: parentToolInsets.bottomEdgeCenterInset + bottomEdgeRightInset: parent.height - attitudeIndicator.y } //------------------------------------------------------------------------- @@ -209,7 +219,7 @@ Item { Rectangle { id: attitudeIndicator - anchors.bottomMargin: _toolsMargin + anchors.bottomMargin: _toolsMargin + parentToolInsets.bottomEdgeRightInset anchors.rightMargin: _toolsMargin anchors.bottom: parent.bottom anchors.right: parent.right From 1a4dc606346df89719c29422c275a009953a4eab Mon Sep 17 00:00:00 2001 From: James Mare Date: Fri, 8 Sep 2023 15:08:34 +1000 Subject: [PATCH 092/118] custom-example: add example of tool inset use this adds a (commented by default) rectangle which uses the tool insets from the widget layer to dynamically size itself. This is an example of how to use tool insets to position something on the custom-layer --- custom-example/res/CustomFlyViewOverlay.qml | 22 ++++++++++++++++++++- 1 file changed, 21 insertions(+), 1 deletion(-) diff --git a/custom-example/res/CustomFlyViewOverlay.qml b/custom-example/res/CustomFlyViewOverlay.qml index 2015f4ff565..422c930a02f 100644 --- a/custom-example/res/CustomFlyViewOverlay.qml +++ b/custom-example/res/CustomFlyViewOverlay.qml @@ -56,7 +56,7 @@ Item { QGCToolInsets { id: _totalToolInsets leftEdgeTopInset: parentToolInsets.leftEdgeTopInset - leftEdgeCenterInset: parentToolInsets.leftEdgeCenterInset + leftEdgeCenterInset: exampleRectangle.leftEdgeCenterInset leftEdgeBottomInset: parentToolInsets.leftEdgeBottomInset rightEdgeTopInset: parentToolInsets.rightEdgeTopInset rightEdgeCenterInset: parentToolInsets.rightEdgeCenterInset @@ -69,6 +69,26 @@ Item { bottomEdgeRightInset: parent.height - attitudeIndicator.y } + // This is an example of how you can use parent tool insets to position an element on the custom fly view layer + // - we use parent topEdgeLeftInset to position the widget below the toolstrip + // - we use parent bottomEdgeLeftInset to dodge the virtual joystick if enabled + // - we use the parent leftEdgeTopInset to size our element to the same width as the ToolStripAction + // - we export the width of this element as the leftEdgeCenterInset so that the map will recenter if the vehicle flys behind this element + Rectangle { + id: exampleRectangle + visible: false // to see this example, set this to true. To view insets, enable the insets viewer FlyView.qml + anchors.left: parent.left + anchors.top: parent.top + anchors.bottom: parent.bottom + anchors.topMargin: parentToolInsets.topEdgeLeftInset + _toolsMargin + anchors.bottomMargin: parentToolInsets.bottomEdgeLeftInset + _toolsMargin + anchors.leftMargin: _toolsMargin + width: parentToolInsets.leftEdgeTopInset - _toolsMargin + color: 'red' + + property real leftEdgeCenterInset: visible ? x + width : 0 + } + //------------------------------------------------------------------------- //-- Heading Indicator Rectangle { From 2290de9cf1569d21b0c09bfaf0eaf0f456564503 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 11 Aug 2023 16:28:22 -0700 Subject: [PATCH 093/118] New translations qgc.ts (Chinese Simplified) --- translations/qgc_source_zh_CN.ts | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/translations/qgc_source_zh_CN.ts b/translations/qgc_source_zh_CN.ts index b8afbb29533..76a68e7169a 100644 --- a/translations/qgc_source_zh_CN.ts +++ b/translations/qgc_source_zh_CN.ts @@ -10170,7 +10170,7 @@ Click Ok to start the auto-tuning process. Item #%1 - 项目 #%1 + 项目 1 From 6e1bed0660b75e1bdb75fc5b81620e689aebccd3 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 15 Aug 2023 20:10:22 -0700 Subject: [PATCH 094/118] New translations qgc.ts (Chinese Simplified) --- translations/qgc_source_zh_CN.ts | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/translations/qgc_source_zh_CN.ts b/translations/qgc_source_zh_CN.ts index 76a68e7169a..dc8b6a57b1a 100644 --- a/translations/qgc_source_zh_CN.ts +++ b/translations/qgc_source_zh_CN.ts @@ -10559,7 +10559,7 @@ Click Ok to start the auto-tuning process. Connected to Vehicle %1 - 已连接到飞机 %1 + 已连接到载具 %1 From 56cc34c5af78e31069a7b14d88ac47a20fc6b000 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Wed, 23 Aug 2023 09:30:30 -0700 Subject: [PATCH 095/118] New translations qgc.ts (Chinese Simplified) --- translations/qgc_source_zh_CN.ts | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/translations/qgc_source_zh_CN.ts b/translations/qgc_source_zh_CN.ts index dc8b6a57b1a..33fcfb8bc53 100644 --- a/translations/qgc_source_zh_CN.ts +++ b/translations/qgc_source_zh_CN.ts @@ -4851,7 +4851,7 @@ Click Ok to start the auto-tuning process. Yaw - 水平 + 偏航 From 12daef2f00d7bb96b6083cb3d284a9a25dbf2189 Mon Sep 17 00:00:00 2001 From: Sergii Lisovenko <2522054+s-lisovenko@users.noreply.github.com> Date: Fri, 20 Oct 2023 11:18:22 +0300 Subject: [PATCH 096/118] Use all mavlink includes instead of ardupilotmega for cmake build Switched mavlink include option from 'ardupilotmega' to 'all' in the CMakeLists file. This modification will allow the use of all the functionalities offered by the mavlink library. the range of functionalities that can be utilized from the mavlink library. --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3c5458874ca..2e7bbdcc990 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -164,7 +164,7 @@ include_directories( libs/libevents libs/mavlink/include/mavlink/v2.0 - libs/mavlink/include/mavlink/v2.0/ardupilotmega + libs/mavlink/include/mavlink/v2.0/all libs/mavlink/include/mavlink/v2.0/common libs/shapelib From 447a2bf43d34c476284726c5add31bda5f4f847c Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Tue, 7 Nov 2023 12:00:01 +0000 Subject: [PATCH 097/118] Update PX4 Firmware metadata Tue Nov 7 12:00:01 UTC 2023 --- .../PX4/PX4ParameterFactMetaData.xml | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 52e82161395..cbad14375a2 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -1020,7 +1020,7 @@ Maximum allowed CPU load to still arm - A negative value disables the check. + The check fails if the CPU load is above this threshold for 2s. A negative value disables the check. -1 100 % @@ -1437,13 +1437,26 @@ 1 - Wind speed RTL threshold - Wind speed threshold above which an automatic return to launch is triggered. It is not possible to resume the mission or switch to any auto mode other than RTL or Land if this threshold is exceeded. Taking over in any manual mode is still possible. Set to -1 to disable. + High wind speed failsafe threshold + Wind speed threshold above which an automatic failsafe action is triggered. Failsafe action can be specified with COM_WIND_MAX_ACT. -1 m/s 1 0.1 + + High wind failsafe mode + Action the system takes when a wind speed above the specified threshold is detected. See COM_WIND_MAX to set the failsafe threshold. If enabled, it is not possible to resume the mission or switch to any auto mode other than RTL or Land if this threshold is exceeded. Taking over in any manual mode is still possible. + 1 + + None + Warning + Hold + Return + Terminate + Land + + Wind speed warning threshold A warning is triggered if the currently estimated wind speed is above this value. Warning is sent periodically (every 1 minute). Set to -1 to disable. From 641c705de1fc9d4888d96e06b4e5509527dfcb58 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Tue, 7 Nov 2023 18:10:53 +0000 Subject: [PATCH 098/118] Update PX4 Firmware metadata Tue Nov 7 18:10:53 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index cbad14375a2..fd12ce5d810 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -5217,7 +5217,7 @@ 1 1 - + Altitude reference mode Set to 0 to control height relative to the earth frame origin. This origin may move up and down in flight due to sensor drift. Set to 1 to control height relative to estimated distance to ground. The vehicle will move up and down with terrain height variation. Requires a distance to ground sensor. The height controller will revert to using height above origin if the distance to ground estimate becomes invalid as indicated by the local_position.distance_bottom_valid message being false. Set to 2 to control height relative to ground (requires a distance sensor) when stationary and relative to earth frame origin when moving horizontally. The speed threshold is controlled by the MPC_HOLD_MAX_XY parameter. 0 From 0f11161900dc3b12f0730f5ba73e16c721cf0e7a Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Thu, 9 Nov 2023 09:26:52 +0000 Subject: [PATCH 099/118] Update PX4 Firmware metadata Thu Nov 9 09:26:52 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index fd12ce5d810..da345d47b59 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -363,7 +363,7 @@ 5 SD - + Wind estimator sideslip measurement noise Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector. 0 @@ -472,7 +472,7 @@ 1/s/sqrt(Hz) 5 - + Gate size for true airspeed fusion Sets the number of standard deviations used by the innovation consistency test. 1 @@ -495,7 +495,7 @@ m/s 3 - + Wind estimator wind process noise spectral density Wind process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. 0 @@ -2465,7 +2465,7 @@ Enable synthetic magnetometer Z component measurement Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value. - + Gate size for TAS fusion Sets the number of standard deviations used by the innovation consistency test. 1.0 @@ -2507,7 +2507,7 @@ m/s 1 - + Process noise spectral density for wind velocity prediction When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. 0.0 From 25595b9c1b8f2a4c6f5250c4b05da9f1d99bdf39 Mon Sep 17 00:00:00 2001 From: James Mare Date: Tue, 4 Jul 2023 12:00:02 +1000 Subject: [PATCH 100/118] ignore unused-but-set-variable on mac builds to suppress errors in QGCTileCacheWorker.cpp and eigen --- QGCCommon.pri | 1 + 1 file changed, 1 insertion(+) diff --git a/QGCCommon.pri b/QGCCommon.pri index d3e1c7888df..f39686c6da3 100644 --- a/QGCCommon.pri +++ b/QGCCommon.pri @@ -107,6 +107,7 @@ linux { QMAKE_CXXFLAGS += -fvisibility=hidden QMAKE_CXXFLAGS_WARN_ON += -Werror \ -Wno-unused-parameter \ # gst-plugins-good + -Wno-unused-but-set-variable \ # eigen & QGCTileCacheWorker.cpp -Wno-deprecated-declarations # eigen } else { error("Unsupported Mac toolchain, only 64-bit LLVM+clang is supported") From cbaec9b858fc29881e1524a4ec030830166af5ba Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Fri, 10 Nov 2023 23:41:11 +0000 Subject: [PATCH 101/118] Update PX4 Firmware metadata Fri Nov 10 23:41:11 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 9 --------- 1 file changed, 9 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index da345d47b59..00eabbd46e9 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -9601,15 +9601,6 @@ Enable stack checking - - Set usage of IO board - Can be used to use a configure the use of the IO board. - true - - IO PWM disabled (RC only) - IO enabled (RC & PWM) - - From d0bf8a35686a91d3274c61304016365627123d39 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Tue, 14 Nov 2023 17:33:10 +0000 Subject: [PATCH 102/118] Update PX4 Firmware metadata Tue Nov 14 17:33:10 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 00eabbd46e9..7b2e2055ae4 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -1429,6 +1429,18 @@ Mission (if valid) + + Enable throw-start + Allows to start the vehicle by throwing it into the air. + + + Minimum speed for the throw start + When the throw launch is enabled, the drone will only arm after this speed is exceeded before detecting the freefall. This is a safety feature to ensure the drone does not turn on after accidental drop or a rapid movement before the throw. Set to 0 to disable. + 0 + m/s + 1 + 0.1 + Horizontal velocity error threshold This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous velocity error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). From a379becf6e7c64924fe1ed05adecb8109c5e8ed4 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Wed, 15 Nov 2023 14:05:15 +0000 Subject: [PATCH 103/118] Update PX4 Firmware metadata Wed Nov 15 14:05:15 UTC 2023 --- .../PX4/PX4ParameterFactMetaData.xml | 120 ------------------ 1 file changed, 120 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 7b2e2055ae4..455b19c59c3 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -1062,126 +1062,6 @@ This number is incremented automatically after every flight on disarming in order to remember the next flight UUID. The first flight is 0. 0 - - First flightmode slot (1000-1160) - If the main switch channel is in this range the selected flight mode will be applied. - - Unassigned - Manual - Altitude - Position - Mission - Hold - Return - Acro - Offboard - Stabilized - Takeoff - Land - Follow Me - Precision Land - - - - Second flightmode slot (1160-1320) - If the main switch channel is in this range the selected flight mode will be applied. - - Unassigned - Manual - Altitude - Position - Mission - Hold - Return - Acro - Offboard - Stabilized - Takeoff - Land - Follow Me - Precision Land - - - - Third flightmode slot (1320-1480) - If the main switch channel is in this range the selected flight mode will be applied. - - Unassigned - Manual - Altitude - Position - Mission - Hold - Return - Acro - Offboard - Stabilized - Takeoff - Land - Follow Me - Precision Land - - - - Fourth flightmode slot (1480-1640) - If the main switch channel is in this range the selected flight mode will be applied. - - Unassigned - Manual - Altitude - Position - Mission - Hold - Return - Acro - Offboard - Stabilized - Takeoff - Land - Follow Me - Precision Land - - - - Fifth flightmode slot (1640-1800) - If the main switch channel is in this range the selected flight mode will be applied. - - Unassigned - Manual - Altitude - Position - Mission - Hold - Return - Acro - Offboard - Stabilized - Takeoff - Land - Follow Me - Precision Land - - - - Sixth flightmode slot (1800-2000) - If the main switch channel is in this range the selected flight mode will be applied. - - Unassigned - Manual - Altitude - Position - Mission - Hold - Return - Acro - Offboard - Stabilized - Takeoff - Land - Follow Me - Precision Land - - User Flight Profile Describes the intended use of the vehicle. Can be used by ground control software or log post processing. This param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params). From 740397e87b4422ef15643553587fe74df39f7fed Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Wed, 15 Nov 2023 10:58:33 -0800 Subject: [PATCH 104/118] Fix up support for Mavlink All dialect --- QGCExternalLibs.pri | 27 +++++++-------------------- custom-example/custom.pri | 1 - 2 files changed, 7 insertions(+), 21 deletions(-) diff --git a/QGCExternalLibs.pri b/QGCExternalLibs.pri index df313799041..ace9afcd190 100644 --- a/QGCExternalLibs.pri +++ b/QGCExternalLibs.pri @@ -55,6 +55,7 @@ isEmpty(MAVLINK_CONF) { message($$sprintf("Using user-supplied mavlink dialect '%1' specified in user_config.pri", $$MAVLINK_CONF)) } else { MAVLINK_CONF = all + message($$sprintf("Using MAVLink dialect '%1'.", $$MAVLINK_CONF)) } } @@ -67,32 +68,18 @@ contains (CONFIG, QGC_DISABLE_APM_MAVLINK) { CONFIG += ArdupilotEnabled } -# First we select the dialect, checking for valid user selection -# Users can override all other settings by specifying MAVLINK_CONF as an argument to qmake -!isEmpty(MAVLINK_CONF) { - message($$sprintf("Using MAVLink dialect '%1'.", $$MAVLINK_CONF)) -} - # Then we add the proper include paths dependent on the dialect. INCLUDEPATH += $$MAVLINKPATH -exists($$MAVLINKPATH/common) { - !isEmpty(MAVLINK_CONF) { - count(MAVLINK_CONF, 1) { - exists($$MAVLINKPATH/$$MAVLINK_CONF) { - INCLUDEPATH += $$MAVLINKPATH/$$MAVLINK_CONF - DEFINES += $$sprintf('QGC_USE_%1_MESSAGES', $$upper($$MAVLINK_CONF)) - } else { - error($$sprintf("MAVLink dialect '%1' does not exist at '%2'!", $$MAVLINK_CONF, $$MAVLINKPATH_REL)) - } - } else { - error(Only a single mavlink dialect can be specified in MAVLINK_CONF) - } +count(MAVLINK_CONF, 1) { + exists($$MAVLINKPATH/$$MAVLINK_CONF) { + INCLUDEPATH += $$MAVLINKPATH/$$MAVLINK_CONF + DEFINES += $$sprintf('QGC_USE_%1_MESSAGES', $$upper($$MAVLINK_CONF)) } else { - INCLUDEPATH += $$MAVLINKPATH/common + error($$sprintf("MAVLink dialect '%1' does not exist at '%2'!", $$MAVLINK_CONF, $$MAVLINKPATH_REL)) } } else { - error($$sprintf("MAVLink folder does not exist at '%1'! Run 'git submodule init && git submodule update' on the command line.",$$MAVLINKPATH_REL)) + error(Only a single mavlink dialect can be specified in MAVLINK_CONF) } # diff --git a/custom-example/custom.pri b/custom-example/custom.pri index b55dd862803..dd5aa4bf362 100644 --- a/custom-example/custom.pri +++ b/custom-example/custom.pri @@ -23,7 +23,6 @@ DEFINES += APP_VERSION_STR=\"\\\"$$CUSTOM_QGC_VERSION\\\"\" message(Custom QGC Version: $${CUSTOM_QGC_VERSION}) # Build a single flight stack by disabling APM support -MAVLINK_CONF = common CONFIG += QGC_DISABLE_APM_MAVLINK CONFIG += QGC_DISABLE_APM_PLUGIN QGC_DISABLE_APM_PLUGIN_FACTORY From 9b660f19fc79f8fef1ac80c0a40db12557c2707f Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Thu, 16 Nov 2023 09:18:17 +0000 Subject: [PATCH 105/118] Update PX4 Firmware metadata Thu Nov 16 09:18:17 UTC 2023 --- .../PX4/PX4ParameterFactMetaData.xml | 18 ------------------ 1 file changed, 18 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 455b19c59c3..d496b9c682f 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -1526,24 +1526,6 @@ m/s^2 2 - - Will be removed after v1.14 release - Set bits in the following positions to enable: 0 : Deprecated, use EKF2_GPS_CTRL instead 1 : Deprecated. use EKF2_OF_CTRL instead 2 : Deprecated, use EKF2_IMU_CTRL instead 3 : Deprecated, use EKF2_EV_CTRL instead 4 : Deprecated, use EKF2_EV_CTRL instead 5 : Deprecated. use EKF2_DRAG_CTRL instead 6 : Deprecated, use EKF2_EV_CTRL instead 7 : Deprecated, use EKF2_GPS_CTRL instead 8 : Deprecated, use EKF2_EV_CTRL instead - 0 - 511 - true - - unused - unused - unused - unused - unused - unused - unused - unused - unused - - 1-sigma tilt angle uncertainty after gravity vector alignment 0.0 From 570548a4d147b03702b8f1a4a7609797275f80f6 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 6 Nov 2023 13:32:25 -0800 Subject: [PATCH 106/118] Fix up support for MAV_RESULT_IN_PROGRESS * Update unit tests to test for in progress * Split result handler into regular ack and in progress ack callbacks --- src/FirmwarePlugin/APM/APMFirmwarePlugin.cc | 16 +-- src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc | 19 +-- src/Vehicle/Actuators/ActuatorActions.cc | 12 +- src/Vehicle/Actuators/ActuatorActions.h | 3 +- src/Vehicle/Actuators/ActuatorTesting.cc | 12 +- src/Vehicle/Actuators/ActuatorTesting.h | 3 +- src/Vehicle/Actuators/MotorAssignment.cc | 12 +- src/Vehicle/Actuators/MotorAssignment.h | 3 +- src/Vehicle/Autotune.cpp | 46 +++++-- src/Vehicle/Autotune.h | 3 +- src/Vehicle/RequestMessageTest.cc | 18 +-- src/Vehicle/SendMavCommandWithHandlerTest.cc | 117 ++++++++++++------ src/Vehicle/SendMavCommandWithHandlerTest.h | 10 +- .../SendMavCommandWithSignallingTest.cc | 11 +- src/Vehicle/Vehicle.cc | 102 +++++++++------ src/Vehicle/Vehicle.h | 80 +++++++----- src/comm/MockLink.cc | 63 +++++++++- src/comm/MockLink.h | 12 +- 18 files changed, 360 insertions(+), 182 deletions(-) diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index f38ffea1548..987826a2a6e 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -777,10 +777,8 @@ typedef struct { Vehicle* vehicle; } MAV_CMD_DO_REPOSITION_HandlerData_t; -static void _MAV_CMD_DO_REPOSITION_ResultHandler(void* resultHandlerData, int /*compId*/, MAV_RESULT commandResult, uint8_t progress, Vehicle::MavCmdResultFailureCode_t failureCode) +static void _MAV_CMD_DO_REPOSITION_ResultHandler(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t /*failureCode*/) { - Q_UNUSED(progress); - auto* data = (MAV_CMD_DO_REPOSITION_HandlerData_t*)resultHandlerData; auto* vehicle = data->vehicle; auto* instanceData = qobject_cast(vehicle->firmwarePluginInstanceData()); @@ -791,8 +789,8 @@ static void _MAV_CMD_DO_REPOSITION_ResultHandler(void* resultHandlerData, int /* goto out; } - instanceData->MAV_CMD_DO_REPOSITION_supported = (commandResult == MAV_RESULT_ACCEPTED); - instanceData->MAV_CMD_DO_REPOSITION_unsupported = (commandResult == MAV_RESULT_UNSUPPORTED); + instanceData->MAV_CMD_DO_REPOSITION_supported = (ack.result == MAV_RESULT_ACCEPTED); + instanceData->MAV_CMD_DO_REPOSITION_unsupported = (ack.result == MAV_RESULT_UNSUPPORTED); out: delete data; @@ -818,9 +816,13 @@ void APMFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord auto* result_handler_data = new MAV_CMD_DO_REPOSITION_HandlerData_t{ vehicle }; + + Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; + handlerInfo.resultHandler = _MAV_CMD_DO_REPOSITION_ResultHandler; + handlerInfo.resultHandlerData = result_handler_data; + vehicle->sendMavCommandIntWithHandler( - _MAV_CMD_DO_REPOSITION_ResultHandler, - result_handler_data, + &handlerInfo, vehicle->defaultComponentId(), MAV_CMD_DO_REPOSITION, MAV_FRAME_GLOBAL, diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 1d75579c5c9..b8fab2716ff 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -494,14 +494,12 @@ typedef struct { double newAMSLAlt; } PauseVehicleThenChangeAltData_t; -static void _pauseVehicleThenChangeAltResultHandler(void* resultHandlerData, int /*compId*/, MAV_RESULT commandResult, uint8_t progress, Vehicle::MavCmdResultFailureCode_t failureCode) +static void _pauseVehicleThenChangeAltResultHandler(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode) { - Q_UNUSED(progress); - - if (commandResult != MAV_RESULT_ACCEPTED) { + if (ack.result != MAV_RESULT_ACCEPTED) { switch (failureCode) { case Vehicle::MavCmdResultCommandResultOnly: - qDebug() << QStringLiteral("MAV_CMD_DO_REPOSITION error(%1)").arg(commandResult); + qDebug() << QStringLiteral("MAV_CMD_DO_REPOSITION error(%1)").arg(ack.result); break; case Vehicle::MavCmdResultFailureNoResponseToCommand: qDebug() << "MAV_CMD_DO_REPOSITION no response from vehicle"; @@ -513,7 +511,7 @@ static void _pauseVehicleThenChangeAltResultHandler(void* resultHandlerData, int } PauseVehicleThenChangeAltData_t* pData = static_cast(resultHandlerData); - pData->plugin->_changeAltAfterPause(resultHandlerData, commandResult == MAV_RESULT_ACCEPTED /* pauseSucceeded */); + pData->plugin->_changeAltAfterPause(resultHandlerData, ack.result == MAV_RESULT_ACCEPTED /* pauseSucceeded */); } void PX4FirmwarePlugin::_changeAltAfterPause(void* resultHandlerData, bool pauseSucceeded) @@ -557,9 +555,12 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu resultData->newAMSLAlt = vehicle->homePosition().altitude() + newAltRel; if (pauseVehicle) { + Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; + handlerInfo.resultHandler = _pauseVehicleThenChangeAltResultHandler; + handlerInfo.resultHandlerData = resultData; + vehicle->sendMavCommandWithHandler( - _pauseVehicleThenChangeAltResultHandler, - resultData, + &handlerInfo, vehicle->defaultComponentId(), MAV_CMD_DO_REPOSITION, -1.0f, // Don't change groundspeed @@ -736,4 +737,4 @@ bool PX4FirmwarePlugin::hasGripper(const Vehicle* vehicle) const return _hasGripper; } return false; -} \ No newline at end of file +} diff --git a/src/Vehicle/Actuators/ActuatorActions.cc b/src/Vehicle/Actuators/ActuatorActions.cc index 81259aed565..555ac42630f 100644 --- a/src/Vehicle/Actuators/ActuatorActions.cc +++ b/src/Vehicle/Actuators/ActuatorActions.cc @@ -39,11 +39,10 @@ void Action::trigger() sendMavlinkRequest(); } -void Action::ackHandlerEntry(void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, - Vehicle::MavCmdResultFailureCode_t failureCode) +void Action::ackHandlerEntry(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode) { Action* action = (Action*)resultHandlerData; - action->ackHandler(commandResult, failureCode); + action->ackHandler(static_cast(ack.result), failureCode); } void Action::ackHandler(MAV_RESULT commandResult, Vehicle::MavCmdResultFailureCode_t failureCode) @@ -58,9 +57,12 @@ void Action::sendMavlinkRequest() { qCDebug(ActuatorsConfigLog) << "Sending actuator action, function:" << _outputFunction << "type:" << (int)_type; + Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; + handlerInfo.resultHandler = ackHandlerEntry; + handlerInfo.resultHandlerData = this; + _vehicle->sendMavCommandWithHandler( - ackHandlerEntry, // Ack callback - this, // Ack callback data + &handlerInfo, MAV_COMP_ID_AUTOPILOT1, // the ID of the autopilot MAV_CMD_CONFIGURE_ACTUATOR, // the mavlink command (int)_type, // action type diff --git a/src/Vehicle/Actuators/ActuatorActions.h b/src/Vehicle/Actuators/ActuatorActions.h index c96c5023e1c..ff27065d1d2 100644 --- a/src/Vehicle/Actuators/ActuatorActions.h +++ b/src/Vehicle/Actuators/ActuatorActions.h @@ -48,8 +48,7 @@ class Action : public QObject Q_INVOKABLE void trigger(); private: - static void ackHandlerEntry(void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, - Vehicle::MavCmdResultFailureCode_t failureCode); + static void ackHandlerEntry(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode); void ackHandler(MAV_RESULT commandResult, Vehicle::MavCmdResultFailureCode_t failureCode); void sendMavlinkRequest(); diff --git a/src/Vehicle/Actuators/ActuatorTesting.cc b/src/Vehicle/Actuators/ActuatorTesting.cc index bee1fd31b3a..ad648b911e0 100644 --- a/src/Vehicle/Actuators/ActuatorTesting.cc +++ b/src/Vehicle/Actuators/ActuatorTesting.cc @@ -120,11 +120,10 @@ void ActuatorTest::setActive(bool active) _active = active; } -void ActuatorTest::ackHandlerEntry(void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, - Vehicle::MavCmdResultFailureCode_t failureCode) +void ActuatorTest::ackHandlerEntry(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode) { ActuatorTest* actuatorTest = (ActuatorTest*)resultHandlerData; - actuatorTest->ackHandler(commandResult, failureCode); + actuatorTest->ackHandler(static_cast(ack.result), failureCode); } void ActuatorTest::ackHandler(MAV_RESULT commandResult, Vehicle::MavCmdResultFailureCode_t failureCode) @@ -190,9 +189,12 @@ void ActuatorTest::sendMavlinkRequest(int function, float value, float timeout) // TODO: consider using a lower command timeout + Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; + handlerInfo.resultHandler = ackHandlerEntry; + handlerInfo.resultHandlerData = this; + _vehicle->sendMavCommandWithHandler( - ackHandlerEntry, // Ack callback - this, // Ack callback data + &handlerInfo, MAV_COMP_ID_AUTOPILOT1, // the ID of the autopilot MAV_CMD_ACTUATOR_TEST, // the mavlink command value, // value diff --git a/src/Vehicle/Actuators/ActuatorTesting.h b/src/Vehicle/Actuators/ActuatorTesting.h index 1c52f386229..de7524957a7 100644 --- a/src/Vehicle/Actuators/ActuatorTesting.h +++ b/src/Vehicle/Actuators/ActuatorTesting.h @@ -110,8 +110,7 @@ class ActuatorTest : public QObject void resetStates(); - static void ackHandlerEntry(void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, - Vehicle::MavCmdResultFailureCode_t failureCode); + static void ackHandlerEntry(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode); void ackHandler(MAV_RESULT commandResult, Vehicle::MavCmdResultFailureCode_t failureCode); void sendMavlinkRequest(int function, float value, float timeout); diff --git a/src/Vehicle/Actuators/MotorAssignment.cc b/src/Vehicle/Actuators/MotorAssignment.cc index b7e087a72da..ea64793f7e9 100644 --- a/src/Vehicle/Actuators/MotorAssignment.cc +++ b/src/Vehicle/Actuators/MotorAssignment.cc @@ -197,11 +197,10 @@ void MotorAssignment::spinTimeout() spinCurrentMotor(); } -void MotorAssignment::ackHandlerEntry(void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, - Vehicle::MavCmdResultFailureCode_t failureCode) +void MotorAssignment::ackHandlerEntry(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode) { MotorAssignment* motorAssignment = (MotorAssignment*)resultHandlerData; - motorAssignment->ackHandler(commandResult, failureCode); + motorAssignment->ackHandler(static_cast(ack.result), failureCode); } void MotorAssignment::ackHandler(MAV_RESULT commandResult, Vehicle::MavCmdResultFailureCode_t failureCode) @@ -217,9 +216,12 @@ void MotorAssignment::sendMavlinkRequest(int function, float value) { qCDebug(ActuatorsConfigLog) << "Sending actuator test function:" << function << "value:" << value; + Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; + handlerInfo.resultHandler = ackHandlerEntry; + handlerInfo.resultHandlerData = this; + _vehicle->sendMavCommandWithHandler( - ackHandlerEntry, // Ack callback - this, // Ack callback data + &handlerInfo, MAV_COMP_ID_AUTOPILOT1, // the ID of the autopilot MAV_CMD_ACTUATOR_TEST, // the mavlink command value, // value diff --git a/src/Vehicle/Actuators/MotorAssignment.h b/src/Vehicle/Actuators/MotorAssignment.h index 1fea827768d..7b7fb60083d 100644 --- a/src/Vehicle/Actuators/MotorAssignment.h +++ b/src/Vehicle/Actuators/MotorAssignment.h @@ -62,8 +62,7 @@ private slots: static constexpr int _spinTimeoutDefaultSec = 1000; static constexpr int _spinTimeoutHighSec = 3000; ///< wait a bit longer after assigning motors, so ESCs can initialize - static void ackHandlerEntry(void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, - Vehicle::MavCmdResultFailureCode_t failureCode); + static void ackHandlerEntry(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode); void ackHandler(MAV_RESULT commandResult, Vehicle::MavCmdResultFailureCode_t failureCode); void sendMavlinkRequest(int function, float value); diff --git a/src/Vehicle/Autotune.cpp b/src/Vehicle/Autotune.cpp index 8b6e18bd2d2..2c7fea17387 100644 --- a/src/Vehicle/Autotune.cpp +++ b/src/Vehicle/Autotune.cpp @@ -41,7 +41,7 @@ void Autotune::autotuneRequest() //----------------------------------------------------------------------------- -void Autotune::ackHandler(void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, Vehicle::MavCmdResultFailureCode_t failureCode) +void Autotune::ackHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode) { Q_UNUSED(compId); Q_UNUSED(failureCode); @@ -49,23 +49,38 @@ void Autotune::ackHandler(void* resultHandlerData, int compId, MAV_RESULT comman auto * autotune = static_cast(resultHandlerData); if (autotune->_autotuneInProgress) { - if ((commandResult == MAV_RESULT_IN_PROGRESS) || (commandResult == MAV_RESULT_ACCEPTED)) { - autotune->handleAckStatus(progress); - } - else if (commandResult == MAV_RESULT_FAILED) { + if (failureCode == Vehicle::MavCmdResultCommandResultOnly) { + if ((ack.result == MAV_RESULT_IN_PROGRESS) || (ack.result == MAV_RESULT_ACCEPTED)) { + autotune->handleAckStatus(ack.progress); + } + else if (ack.result == MAV_RESULT_FAILED) { + autotune->handleAckFailure(); + } + else { + autotune->handleAckError(ack.result); + } + } else { autotune->handleAckFailure(); } - else { - autotune->handleAckError(commandResult); - } - emit autotune->autotuneChanged(); - } - else { + } else { qWarning() << "Ack received for a command different from MAV_CMD_DO_AUTOTUNE_ENABLE ot wrong UI state."; } } +void Autotune::progressHandler(void* progressHandlerData, int compId, const mavlink_command_ack_t& ack) +{ + Q_UNUSED(compId); + + auto * autotune = static_cast(progressHandlerData); + + if (autotune->_autotuneInProgress) { + autotune->handleAckStatus(ack.progress); + emit autotune->autotuneChanged(); + } else { + qWarning() << "Ack received for a command different from MAV_CMD_DO_AUTOTUNE_ENABLE ot wrong UI state."; + } +} //----------------------------------------------------------------------------- bool Autotune::autotuneEnabled() @@ -162,9 +177,14 @@ void Autotune::stopTimers() //----------------------------------------------------------------------------- void Autotune::sendMavlinkRequest() { + Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; + handlerInfo.resultHandler = ackHandler; + handlerInfo.resultHandlerData = this; + handlerInfo.progressHandler = progressHandler; + handlerInfo.progressHandlerData = this; + _vehicle->sendMavCommandWithHandler( - ackHandler, // Ack callback - this, // Ack callback data + &handlerInfo, MAV_COMP_ID_AUTOPILOT1, // the ID of the autopilot MAV_CMD_DO_AUTOTUNE_ENABLE, // the mavlink command 1, // request autotune diff --git a/src/Vehicle/Autotune.h b/src/Vehicle/Autotune.h index 6da18839bb1..e7019fdfa86 100644 --- a/src/Vehicle/Autotune.h +++ b/src/Vehicle/Autotune.h @@ -28,7 +28,8 @@ class Autotune : public QObject Q_INVOKABLE void autotuneRequest (); - static void ackHandler(void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, Vehicle::MavCmdResultFailureCode_t failureCode); + static void ackHandler (void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode); + static void progressHandler (void* progressHandlerData, int compId, const mavlink_command_ack_t& ack); bool autotuneEnabled (); bool autotuneInProgress () { return _autotuneInProgress; } diff --git a/src/Vehicle/RequestMessageTest.cc b/src/Vehicle/RequestMessageTest.cc index 12e90c5af97..c4224755d01 100644 --- a/src/Vehicle/RequestMessageTest.cc +++ b/src/Vehicle/RequestMessageTest.cc @@ -38,21 +38,21 @@ void RequestMessageTest::_testCaseWorker(TestCase_t& testCase) MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); Vehicle* vehicle = vehicleMgr->activeVehicle(); - _mockLink->clearSendMavCommandCounts(); + _mockLink->clearReceivedMavCommandCounts(); _mockLink->setRequestMessageFailureMode(testCase.failureMode); vehicle->requestMessage(_requestMessageResultHandler, &testCase, MAV_COMP_ID_AUTOPILOT1, MAVLINK_MSG_ID_DEBUG); QVERIFY(QTest::qWaitFor([&]() { return testCase.resultHandlerCalled; }, 10000)); QCOMPARE(vehicle->_findMavCommandListEntryIndex(MAV_COMP_ID_AUTOPILOT1, MAV_CMD_REQUEST_MESSAGE), -1); - QCOMPARE(_mockLink->sendMavCommandCount(MAV_CMD_REQUEST_MESSAGE), testCase.expectedSendCount); + QCOMPARE(_mockLink->receivedMavCommandCount(MAV_CMD_REQUEST_MESSAGE), testCase.expectedSendCount); // We should be able to do it twice in a row without any duplicate command problems testCase.resultHandlerCalled = false; - _mockLink->clearSendMavCommandCounts(); + _mockLink->clearReceivedMavCommandCounts(); vehicle->requestMessage(_requestMessageResultHandler, &testCase, MAV_COMP_ID_AUTOPILOT1, MAVLINK_MSG_ID_DEBUG); QVERIFY(QTest::qWaitFor([&]() { return testCase.resultHandlerCalled; }, 10000)); QCOMPARE(vehicle->_findMavCommandListEntryIndex(MAV_COMP_ID_AUTOPILOT1, MAV_CMD_REQUEST_MESSAGE), -1); - QCOMPARE(_mockLink->sendMavCommandCount(MAV_CMD_REQUEST_MESSAGE), testCase.expectedSendCount); + QCOMPARE(_mockLink->receivedMavCommandCount(MAV_CMD_REQUEST_MESSAGE), testCase.expectedSendCount); _disconnectMockLink(); } @@ -77,19 +77,19 @@ void RequestMessageTest::_duplicateCommand(void) MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); Vehicle* vehicle = vehicleMgr->activeVehicle(); - _mockLink->clearSendMavCommandCounts(); + _mockLink->clearReceivedMavCommandCounts(); _mockLink->setRequestMessageFailureMode(testCase.failureMode); QVERIFY(false == vehicle->isMavCommandPending(MAV_COMP_ID_AUTOPILOT1, MAV_CMD_REQUEST_MESSAGE)); vehicle->requestMessage(_requestMessageResultHandler, &testCase, MAV_COMP_ID_AUTOPILOT1, MAVLINK_MSG_ID_DEBUG); - QVERIFY(QTest::qWaitFor([&]() { return _mockLink->sendMavCommandCount(MAV_CMD_REQUEST_MESSAGE) == 1; }, 10)); + QVERIFY(QTest::qWaitFor([&]() { return _mockLink->receivedMavCommandCount(MAV_CMD_REQUEST_MESSAGE) == 1; }, 10)); QCOMPARE(testCase.resultHandlerCalled, false); vehicle->requestMessage(_requestMessageResultHandler, &testCase, MAV_COMP_ID_AUTOPILOT1, MAVLINK_MSG_ID_DEBUG); // Duplicate command returns immediately QCOMPARE(testCase.resultHandlerCalled, true); - QCOMPARE(_mockLink->sendMavCommandCount(MAV_CMD_REQUEST_MESSAGE), testCase.expectedSendCount); + QCOMPARE(_mockLink->receivedMavCommandCount(MAV_CMD_REQUEST_MESSAGE), testCase.expectedSendCount); QVERIFY(vehicle->_findMavCommandListEntryIndex(MAV_COMP_ID_AUTOPILOT1, MAV_CMD_REQUEST_MESSAGE) != -1); QVERIFY(true == vehicle->isMavCommandPending(MAV_COMP_ID_AUTOPILOT1, MAV_CMD_REQUEST_MESSAGE)); @@ -123,13 +123,13 @@ void RequestMessageTest::_compIdAllFailure(void) MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); Vehicle* vehicle = vehicleMgr->activeVehicle(); - _mockLink->clearSendMavCommandCounts(); + _mockLink->clearReceivedMavCommandCounts(); _mockLink->setRequestMessageFailureMode(testCase.failureMode); vehicle->requestMessage(_requestMessageResultHandler, &testCase, MAV_COMP_ID_ALL, MAVLINK_MSG_ID_DEBUG); QCOMPARE(testCase.resultHandlerCalled, true); QCOMPARE(vehicle->_findMavCommandListEntryIndex(MAV_COMP_ID_ALL, MAV_CMD_REQUEST_MESSAGE), -1); - QCOMPARE(_mockLink->sendMavCommandCount(MAV_CMD_REQUEST_MESSAGE), 0); + QCOMPARE(_mockLink->receivedMavCommandCount(MAV_CMD_REQUEST_MESSAGE), 0); _disconnectMockLink(); } diff --git a/src/Vehicle/SendMavCommandWithHandlerTest.cc b/src/Vehicle/SendMavCommandWithHandlerTest.cc index bf403ac374d..6f6023c38e1 100644 --- a/src/Vehicle/SendMavCommandWithHandlerTest.cc +++ b/src/Vehicle/SendMavCommandWithHandlerTest.cc @@ -13,28 +13,47 @@ #include "MockLink.h" SendMavCommandWithHandlerTest::TestCase_t SendMavCommandWithHandlerTest::_rgTestCases[] = { - { MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_ACCEPTED, MAV_RESULT_ACCEPTED, 0, Vehicle::MavCmdResultCommandResultOnly, 1 }, - { MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_FAILED, MAV_RESULT_FAILED, 0, Vehicle::MavCmdResultCommandResultOnly, 1 }, - { MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_ACCEPTED, MAV_RESULT_ACCEPTED, 0, Vehicle::MavCmdResultCommandResultOnly, 2 }, - { MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED, MAV_RESULT_FAILED, 0, Vehicle::MavCmdResultCommandResultOnly, 2 }, - { MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE, MAV_RESULT_FAILED, 0, Vehicle::MavCmdResultFailureNoResponseToCommand, Vehicle::_mavCommandMaxRetryCount }, - { MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE_NO_RETRY, MAV_RESULT_FAILED, 0, Vehicle::MavCmdResultFailureNoResponseToCommand, 1 }, + { MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_ACCEPTED, MAV_RESULT_ACCEPTED, false, Vehicle::MavCmdResultCommandResultOnly, 1 }, + { MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_FAILED, MAV_RESULT_FAILED, false, Vehicle::MavCmdResultCommandResultOnly, 1 }, + { MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_ACCEPTED, MAV_RESULT_ACCEPTED, false, Vehicle::MavCmdResultCommandResultOnly, 2 }, + { MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED, MAV_RESULT_FAILED, false, Vehicle::MavCmdResultCommandResultOnly, 2 }, + { MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE, MAV_RESULT_FAILED, false, Vehicle::MavCmdResultFailureNoResponseToCommand, Vehicle::_mavCommandMaxRetryCount }, + { MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE_NO_RETRY, MAV_RESULT_FAILED, false, Vehicle::MavCmdResultFailureNoResponseToCommand, 1 }, + { MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_ACCEPTED, MAV_RESULT_ACCEPTED, true, Vehicle::MavCmdResultCommandResultOnly, 1 }, + { MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_FAILED, MAV_RESULT_FAILED, true, Vehicle::MavCmdResultCommandResultOnly, 1 }, + { MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_NO_ACK, MAV_RESULT_FAILED, true, Vehicle::MavCmdResultFailureNoResponseToCommand, 1 }, }; -bool SendMavCommandWithHandlerTest::_handlerCalled = false; +bool SendMavCommandWithHandlerTest::_resultHandlerCalled = false; +bool SendMavCommandWithHandlerTest::_progressHandlerCalled = false; -void SendMavCommandWithHandlerTest::_mavCmdResultHandler(void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, Vehicle::MavCmdResultFailureCode_t failureCode) +void SendMavCommandWithHandlerTest::_mavCmdResultHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode) { TestCase_t* testCase = static_cast(resultHandlerData); - _handlerCalled = true; + _resultHandlerCalled = true; - QCOMPARE(compId, MAV_COMP_ID_AUTOPILOT1); - QCOMPARE(testCase->expectedCommandResult, commandResult); - QCOMPARE(testCase->progress, progress); + QCOMPARE(MAV_COMP_ID_AUTOPILOT1, compId); + QCOMPARE(testCase->expectedCommandResult, ack.result); QCOMPARE(testCase->expectedFailureCode, failureCode); } +void SendMavCommandWithHandlerTest::_mavCmdProgressHandler(void* progressHandlerData, int compId, const mavlink_command_ack_t& ack) +{ + TestCase_t* testCase = static_cast(progressHandlerData); + MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + Vehicle* vehicle = vehicleMgr->activeVehicle(); + + _progressHandlerCalled = true; + + QCOMPARE(MAV_COMP_ID_AUTOPILOT1, compId); + QCOMPARE(MAV_RESULT_IN_PROGRESS, ack.result); + QCOMPARE(1, ack.progress); + + // Command should still be in list + QVERIFY(vehicle->_findMavCommandListEntryIndex(MAV_COMP_ID_AUTOPILOT1, testCase->command) != -1); +} + void SendMavCommandWithHandlerTest::_testCaseWorker(TestCase_t& testCase) { _connectMockLinkNoInitialConnectSequence(); @@ -42,12 +61,25 @@ void SendMavCommandWithHandlerTest::_testCaseWorker(TestCase_t& testCase) MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); Vehicle* vehicle = vehicleMgr->activeVehicle(); - _handlerCalled = false; - _mockLink->clearSendMavCommandCounts(); - vehicle->sendMavCommandWithHandler(_mavCmdResultHandler, &testCase, MAV_COMP_ID_AUTOPILOT1, testCase.command); - QVERIFY(QTest::qWaitFor([&]() { return _handlerCalled; }, 10000)); - QCOMPARE(vehicle->_findMavCommandListEntryIndex(MAV_COMP_ID_AUTOPILOT1, testCase.command), -1); - QCOMPARE(_mockLink->sendMavCommandCount(testCase.command), testCase.expectedSendCount); + Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; + handlerInfo.resultHandler = _mavCmdResultHandler; + handlerInfo.resultHandlerData = &testCase; + handlerInfo.progressHandler = _mavCmdProgressHandler; + handlerInfo.progressHandlerData = &testCase; + + _resultHandlerCalled = false; + _progressHandlerCalled = false; + + _mockLink->clearReceivedMavCommandCounts(); + vehicle->sendMavCommandWithHandler(&handlerInfo, MAV_COMP_ID_AUTOPILOT1, testCase.command); + + if (testCase.expectInProgressResult) { + QVERIFY(QTest::qWaitFor([&]() { return _progressHandlerCalled; }, 10000)); + } + + QVERIFY(QTest::qWaitFor([&]() { return _resultHandlerCalled; }, 10000)); + QCOMPARE(_mockLink->receivedMavCommandCount(testCase.command), testCase.expectedSendCount); + QCOMPARE(vehicle->_findMavCommandListEntryIndex(MAV_COMP_ID_AUTOPILOT1, testCase.command), -1); _disconnectMockLink(); } @@ -72,27 +104,35 @@ void SendMavCommandWithHandlerTest::_duplicateCommand(void) MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); Vehicle* vehicle = vehicleMgr->activeVehicle(); - _handlerCalled = false; - _mockLink->clearSendMavCommandCounts(); + Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; + handlerInfo.resultHandler = _mavCmdResultHandler; + handlerInfo.resultHandlerData = &testCase; + handlerInfo.progressHandler = _mavCmdProgressHandler; + handlerInfo.progressHandlerData = &testCase; + + _resultHandlerCalled = false; + _progressHandlerCalled = false; + + _mockLink->clearReceivedMavCommandCounts(); vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1, testCase.command, true /* showError */); - QVERIFY(QTest::qWaitFor([&]() { return _mockLink->sendMavCommandCount(testCase.command) == 1; }, 10)); - QVERIFY(!_handlerCalled); - vehicle->sendMavCommandWithHandler(_mavCmdResultHandler, &testCase, MAV_COMP_ID_AUTOPILOT1, testCase.command); + QVERIFY(QTest::qWaitFor([&]() { return _mockLink->receivedMavCommandCount(testCase.command) == 1; }, 10)); + QVERIFY(!_resultHandlerCalled); + QVERIFY(!_progressHandlerCalled); + vehicle->sendMavCommandWithHandler(&handlerInfo, MAV_COMP_ID_AUTOPILOT1, testCase.command); // Duplicate command response should happen immediately - QVERIFY(_handlerCalled); + QVERIFY(_resultHandlerCalled); QVERIFY(vehicle->_findMavCommandListEntryIndex(MAV_COMP_ID_AUTOPILOT1, testCase.command) != -1); - QCOMPARE(_mockLink->sendMavCommandCount(testCase.command), 1); + QCOMPARE(_mockLink->receivedMavCommandCount(testCase.command), 1); } -void SendMavCommandWithHandlerTest::_compIdAllMavCmdResultHandler(void* /*resultHandlerData*/, int compId, MAV_RESULT commandResult, uint8_t progress, Vehicle::MavCmdResultFailureCode_t failureCode) +void SendMavCommandWithHandlerTest::_compIdAllFailureMavCmdResultHandler(void* /*resultHandlerData*/, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode) { - _handlerCalled = true; + _resultHandlerCalled = true; - QCOMPARE(compId, MAV_COMP_ID_ALL); - QCOMPARE(commandResult, MAV_RESULT_FAILED); - QCOMPARE(progress, 0); - QCOMPARE(failureCode, Vehicle::MavCmdResultCommandResultOnly); + QCOMPARE(compId, MAV_COMP_ID_ALL); + QCOMPARE(ack.result, MAV_RESULT_FAILED); + QCOMPARE(failureCode, Vehicle::MavCmdResultCommandResultOnly); } void SendMavCommandWithHandlerTest::_compIdAllFailure(void) @@ -106,12 +146,17 @@ void SendMavCommandWithHandlerTest::_compIdAllFailure(void) MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); Vehicle* vehicle = vehicleMgr->activeVehicle(); - _handlerCalled = false; - _mockLink->clearSendMavCommandCounts(); - vehicle->sendMavCommandWithHandler(_compIdAllMavCmdResultHandler, nullptr, MAV_COMP_ID_ALL, testCase.command); - QCOMPARE(_handlerCalled, true); + Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; + handlerInfo.resultHandler = _compIdAllFailureMavCmdResultHandler; + + _resultHandlerCalled = false; + + _mockLink->clearReceivedMavCommandCounts(); + vehicle->sendMavCommandWithHandler(&handlerInfo, MAV_COMP_ID_ALL, testCase.command); + + QCOMPARE(_resultHandlerCalled, true); QCOMPARE(vehicle->_findMavCommandListEntryIndex(MAV_COMP_ID_ALL, testCase.command), -1); - QCOMPARE(_mockLink->sendMavCommandCount(testCase.command), testCase.expectedSendCount); + QCOMPARE(_mockLink->receivedMavCommandCount(testCase.command), testCase.expectedSendCount); _disconnectMockLink(); } diff --git a/src/Vehicle/SendMavCommandWithHandlerTest.h b/src/Vehicle/SendMavCommandWithHandlerTest.h index 4f70bd01d27..1d97c5ef8c0 100644 --- a/src/Vehicle/SendMavCommandWithHandlerTest.h +++ b/src/Vehicle/SendMavCommandWithHandlerTest.h @@ -25,17 +25,19 @@ private slots: typedef struct { MAV_CMD command; MAV_RESULT expectedCommandResult; - uint8_t progress; + bool expectInProgressResult; Vehicle::MavCmdResultFailureCode_t expectedFailureCode; int expectedSendCount; } TestCase_t; void _testCaseWorker(TestCase_t& testCase); - static void _mavCmdResultHandler (void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, Vehicle::MavCmdResultFailureCode_t failureCode); - static void _compIdAllMavCmdResultHandler (void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, Vehicle::MavCmdResultFailureCode_t failureCode); + static void _mavCmdResultHandler (void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode); + static void _mavCmdProgressHandler (void* progressHandlerData, int compId, const mavlink_command_ack_t& ack); + static void _compIdAllFailureMavCmdResultHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode); - static bool _handlerCalled; + static bool _resultHandlerCalled; + static bool _progressHandlerCalled; static TestCase_t _rgTestCases[]; }; diff --git a/src/Vehicle/SendMavCommandWithSignallingTest.cc b/src/Vehicle/SendMavCommandWithSignallingTest.cc index a5b0139bcc0..ff1c26ecd5f 100644 --- a/src/Vehicle/SendMavCommandWithSignallingTest.cc +++ b/src/Vehicle/SendMavCommandWithSignallingTest.cc @@ -19,6 +19,9 @@ SendMavCommandWithSignallingTest::TestCase_t SendMavCommandWithSignallingTest::_ { MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED, MAV_RESULT_FAILED, Vehicle::MavCmdResultCommandResultOnly, 2 }, { MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE, MAV_RESULT_FAILED, Vehicle::MavCmdResultFailureNoResponseToCommand, Vehicle::_mavCommandMaxRetryCount }, { MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE_NO_RETRY, MAV_RESULT_FAILED, Vehicle::MavCmdResultFailureNoResponseToCommand, 1 }, + { MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_ACCEPTED, MAV_RESULT_ACCEPTED, Vehicle::MavCmdResultCommandResultOnly, 1 }, + { MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_FAILED, MAV_RESULT_FAILED, Vehicle::MavCmdResultCommandResultOnly, 1 }, + { MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_NO_ACK, MAV_RESULT_FAILED, Vehicle::MavCmdResultFailureNoResponseToCommand, 1 }, }; void SendMavCommandWithSignallingTest::_testCaseWorker(TestCase_t& testCase) @@ -29,7 +32,7 @@ void SendMavCommandWithSignallingTest::_testCaseWorker(TestCase_t& testCase) Vehicle* vehicle = vehicleMgr->activeVehicle(); QSignalSpy spyResult(vehicle, &Vehicle::mavCommandResult); - _mockLink->clearSendMavCommandCounts(); + _mockLink->clearReceivedMavCommandCounts(); vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1, testCase.command, true /* showError */); @@ -42,7 +45,7 @@ void SendMavCommandWithSignallingTest::_testCaseWorker(TestCase_t& testCase) QCOMPARE(arguments.at(3).toInt(), testCase.expectedCommandResult); QCOMPARE(arguments.at(4).value(), testCase.expectedFailureCode); QCOMPARE(vehicle->_findMavCommandListEntryIndex(MAV_COMP_ID_AUTOPILOT1, MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_ACCEPTED), -1); - QCOMPARE(_mockLink->sendMavCommandCount(testCase.command), testCase.expectedSendCount); + QCOMPARE(_mockLink->receivedMavCommandCount(testCase.command), testCase.expectedSendCount); _disconnectMockLink(); } @@ -64,7 +67,7 @@ void SendMavCommandWithSignallingTest::_duplicateCommand(void) Vehicle* vehicle = vehicleMgr->activeVehicle(); vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1, MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE, true /* showError */); - QVERIFY(QTest::qWaitFor([&]() { return _mockLink->sendMavCommandCount(MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE) == 1; }, 10)); + QVERIFY(QTest::qWaitFor([&]() { return _mockLink->receivedMavCommandCount(MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE) == 1; }, 10)); QSignalSpy spyResult(vehicle, &Vehicle::mavCommandResult); vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1, MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE, true /* showError */); @@ -76,6 +79,6 @@ void SendMavCommandWithSignallingTest::_duplicateCommand(void) QCOMPARE(arguments.at(2).toInt(), (int)MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE); QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_FAILED); QCOMPARE(arguments.at(4).value(), Vehicle::MavCmdResultFailureDuplicateCommand); - QCOMPARE(_mockLink->sendMavCommandCount(MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE), 1); + QCOMPARE(_mockLink->receivedMavCommandCount(MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE), 1); QVERIFY(vehicle->_findMavCommandListEntryIndex(MAV_COMP_ID_AUTOPILOT1, MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE) != -1); } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index a82fa790dae..5962b4b2b24 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -2960,8 +2960,7 @@ void Vehicle::sendMavCommand(int compId, MAV_CMD command, bool showError, float { _sendMavCommandWorker(false, // commandInt showError, - nullptr, // resultHandler - nullptr, // resultHandlerData + nullptr, // no handlers compId, command, MAV_FRAME_GLOBAL, @@ -2982,12 +2981,11 @@ void Vehicle::sendCommand(int compId, int command, bool showError, double param1 static_cast(param7)); } -void Vehicle::sendMavCommandWithHandler(MavCmdResultHandler resultHandler, void *resultHandlerData, int compId, MAV_CMD command, float param1, float param2, float param3, float param4, float param5, float param6, float param7) +void Vehicle::sendMavCommandWithHandler(const MavCmdAckHandlerInfo_t* ackHandlerInfo, int compId, MAV_CMD command, float param1, float param2, float param3, float param4, float param5, float param6, float param7) { _sendMavCommandWorker(false, // commandInt false, // showError - resultHandler, - resultHandlerData, + ackHandlerInfo, compId, command, MAV_FRAME_GLOBAL, @@ -2998,20 +2996,18 @@ void Vehicle::sendMavCommandInt(int compId, MAV_CMD command, MAV_FRAME frame, bo { _sendMavCommandWorker(true, // commandInt showError, - nullptr, // resultHandler - nullptr, // resultHandlerData + nullptr, // no handlers compId, command, frame, param1, param2, param3, param4, param5, param6, param7); } -void Vehicle::sendMavCommandIntWithHandler(MavCmdResultHandler resultHandler, void *resultHandlerData, int compId, MAV_CMD command, MAV_FRAME frame, float param1, float param2, float param3, float param4, double param5, double param6, float param7) +void Vehicle::sendMavCommandIntWithHandler(const MavCmdAckHandlerInfo_t* ackHandlerInfo, int compId, MAV_CMD command, MAV_FRAME frame, float param1, float param2, float param3, float param4, double param5, double param6, float param7) { _sendMavCommandWorker(true, // commandInt false, // showError - resultHandler, - resultHandlerData, + ackHandlerInfo, compId, command, frame, @@ -3080,19 +3076,30 @@ bool Vehicle::_commandCanBeDuplicated(MAV_CMD command) } } -void Vehicle::_sendMavCommandWorker(bool commandInt, bool showError, MavCmdResultHandler resultHandler, void* resultHandlerData, int targetCompId, MAV_CMD command, MAV_FRAME frame, float param1, float param2, float param3, float param4, double param5, double param6, float param7) +void Vehicle::_sendMavCommandWorker( + bool commandInt, + bool showError, + const MavCmdAckHandlerInfo_t* ackHandlerInfo, + int targetCompId, + MAV_CMD command, + MAV_FRAME frame, + float param1, float param2, float param3, float param4, double param5, double param6, float param7) { + // We can't send commands to compIdAll using this method. The reason being that we would get responses back possibly from multiple components + // which this code can't handle. + // We also can't send the majority of commands again if we are already waiting for a response from that same command. If we did that we would not be able to discern + // which ack was associated with which command. if ((targetCompId == MAV_COMP_ID_ALL) || (isMavCommandPending(targetCompId, command) && !_commandCanBeDuplicated(command))) { bool compIdAll = targetCompId == MAV_COMP_ID_ALL; QString rawCommandName = _toolbox->missionCommandTree()->rawName(command); qCDebug(VehicleLog) << QStringLiteral("_sendMavCommandWorker failing %1").arg(compIdAll ? "MAV_COMP_ID_ALL not supportded" : "duplicate command") << rawCommandName; - // If we send multiple versions of the same command to a component there is no way to discern which COMMAND_ACK we get back goes with which. - // Because of this we fail in that case. MavCmdResultFailureCode_t failureCode = compIdAll ? MavCmdResultCommandResultOnly : MavCmdResultFailureDuplicateCommand; - if (resultHandler) { - (*resultHandler)(resultHandlerData, targetCompId, MAV_RESULT_FAILED, 0, failureCode); + if (ackHandlerInfo && ackHandlerInfo->resultHandler) { + mavlink_command_ack_t ack = {}; + ack.result = MAV_RESULT_FAILED; + (*ackHandlerInfo->resultHandler)(ackHandlerInfo->resultHandlerData, targetCompId, ack, failureCode); } else { emit mavCommandResult(_id, targetCompId, command, MAV_RESULT_FAILED, failureCode); } @@ -3116,8 +3123,10 @@ void Vehicle::_sendMavCommandWorker(bool commandInt, bool showError, MavCmdResul entry.command = command; entry.frame = frame; entry.showError = showError; - entry.resultHandler = resultHandler; - entry.resultHandlerData = resultHandlerData; + entry.ackHandlerInfo = {}; + if (ackHandlerInfo) { + entry.ackHandlerInfo = *ackHandlerInfo; + } entry.rgParam1 = param1; entry.rgParam2 = param2; entry.rgParam3 = param3; @@ -3142,8 +3151,10 @@ void Vehicle::_sendMavCommandFromList(int index) if (++_mavCommandList[index].tryCount > commandEntry.maxTries) { qCDebug(VehicleLog) << "_sendMavCommandFromList giving up after max retries" << rawCommandName; _mavCommandList.removeAt(index); - if (commandEntry.resultHandler) { - (*commandEntry.resultHandler)(commandEntry.resultHandlerData, commandEntry.targetCompId, MAV_RESULT_FAILED, 0, MavCmdResultFailureNoResponseToCommand); + if (commandEntry.ackHandlerInfo.resultHandler) { + mavlink_command_ack_t ack = {}; + ack.result = MAV_RESULT_FAILED; + (*commandEntry.ackHandlerInfo.resultHandler)(commandEntry.ackHandlerInfo.resultHandlerData, commandEntry.targetCompId, ack, MavCmdResultFailureNoResponseToCommand); } else { emit mavCommandResult(_id, commandEntry.targetCompId, commandEntry.command, MAV_RESULT_FAILED, MavCmdResultFailureNoResponseToCommand); } @@ -3264,12 +3275,21 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message) #endif int entryIndex = _findMavCommandListEntryIndex(message.compid, static_cast(ack.command)); - bool commandInList = false; if (entryIndex != -1) { - MavCommandListEntry_t commandEntry = _mavCommandList.takeAt(entryIndex); - if (commandEntry.command == ack.command) { - if (commandEntry.resultHandler) { - (*commandEntry.resultHandler)(commandEntry.resultHandlerData, message.compid, static_cast(ack.result), ack.progress, MavCmdResultCommandResultOnly); + if (ack.result == MAV_RESULT_IN_PROGRESS) { + MavCommandListEntry_t commandEntry = _mavCommandList.at(entryIndex); // Command has not completed yet, don't remove + + commandEntry.maxTries = 1; // Vehicle responsed to command so don't retry + commandEntry.elapsedTimer.restart(); // We've heard from vehicle, restart elapsed timer for no ack received timeout + + if (commandEntry.ackHandlerInfo.progressHandler) { + (*commandEntry.ackHandlerInfo.progressHandler)(commandEntry.ackHandlerInfo.progressHandlerData, message.compid, ack); + } + } else { + MavCommandListEntry_t commandEntry = _mavCommandList.takeAt(entryIndex); + + if (commandEntry.ackHandlerInfo.resultHandler) { + (*commandEntry.ackHandlerInfo.resultHandler)(commandEntry.ackHandlerInfo.resultHandlerData, message.compid, ack, MavCmdResultCommandResultOnly); } else { if (commandEntry.showError) { switch (ack.result) { @@ -3292,11 +3312,8 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message) } emit mavCommandResult(_id, message.compid, ack.command, ack.result, MavCmdResultCommandResultOnly); } - commandInList = true; } - } - - if (!commandInList) { + } else { qCDebug(VehicleLog) << "_handleCommandAck Ack not in list" << rawCommandName; } @@ -3360,10 +3377,13 @@ void Vehicle::requestMessage(RequestMessageResultHandler resultHandler, void* re _waitForMavlinkMessage(_requestMessageWaitForMessageResultHandler, pInfo, pInfo->msgId, 1000); + Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; + handlerInfo.resultHandler = _requestMessageCmdResultHandler; + handlerInfo.resultHandlerData = pInfo; + _sendMavCommandWorker(false, // commandInt false, // showError - _requestMessageCmdResultHandler, - pInfo, // resultHandlerData + &handlerInfo, compId, MAV_CMD_REQUEST_MESSAGE, MAV_FRAME_GLOBAL, @@ -3371,13 +3391,13 @@ void Vehicle::requestMessage(RequestMessageResultHandler resultHandler, void* re param1, param2, param3, param4, param5, 0); } -void Vehicle::_requestMessageCmdResultHandler(void* resultHandlerData, int /*compId*/, MAV_RESULT result, uint8_t progress, MavCmdResultFailureCode_t failureCode) +void Vehicle::_requestMessageCmdResultHandler(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode) { RequestMessageInfo_t* pInfo = static_cast(resultHandlerData); Vehicle* vehicle = pInfo->vehicle; pInfo->commandAckReceived = true; - if (result != MAV_RESULT_ACCEPTED) { + if (ack.result != MAV_RESULT_ACCEPTED) { mavlink_message_t message; RequestMessageResultHandlerFailureCode_t requestMessageFailureCode; @@ -3394,12 +3414,12 @@ void Vehicle::_requestMessageCmdResultHandler(void* resultHandlerData, int /*com } vehicle->_waitForMavlinkMessageClear(); - (*pInfo->resultHandler)(pInfo->resultHandlerData, result, requestMessageFailureCode, message); + (*pInfo->resultHandler)(pInfo->resultHandlerData, static_cast(ack.result), requestMessageFailureCode, message); return; } if (pInfo->messageReceived) { - (*pInfo->resultHandler)(pInfo->resultHandlerData, result, RequestMessageNoFailure, pInfo->message); + (*pInfo->resultHandler)(pInfo->resultHandlerData, static_cast(ack.result), RequestMessageNoFailure, pInfo->message); delete pInfo; } else { vehicle->_waitForMavlinkMessageTimeoutActive = true; @@ -3468,16 +3488,14 @@ QString Vehicle::firmwareVersionTypeString() const } } -void Vehicle::_rebootCommandResultHandler(void* resultHandlerData, int /*compId*/, MAV_RESULT commandResult, uint8_t progress, MavCmdResultFailureCode_t failureCode) +void Vehicle::_rebootCommandResultHandler(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode) { - Q_UNUSED(progress) - Vehicle* vehicle = static_cast(resultHandlerData); - if (commandResult != MAV_RESULT_ACCEPTED) { + if (ack.result != MAV_RESULT_ACCEPTED) { switch (failureCode) { case MavCmdResultCommandResultOnly: - qCDebug(VehicleLog) << QStringLiteral("MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN error(%1)").arg(commandResult); + qCDebug(VehicleLog) << QStringLiteral("MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN error(%1)").arg(ack.result); break; case MavCmdResultFailureNoResponseToCommand: qCDebug(VehicleLog) << "MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN failed: no response from vehicle"; @@ -3494,7 +3512,11 @@ void Vehicle::_rebootCommandResultHandler(void* resultHandlerData, int /*compId* void Vehicle::rebootVehicle() { - sendMavCommandWithHandler(_rebootCommandResultHandler, this, _defaultComponentId, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1); + Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; + handlerInfo.resultHandler = _rebootCommandResultHandler; + handlerInfo.resultHandlerData = this; + + sendMavCommandWithHandler(&handlerInfo, _defaultComponentId, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1); } void Vehicle::startCalibration(Vehicle::CalibrationType calType) diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 1eb292fa4fc..5a61c786aa6 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -763,21 +763,38 @@ class Vehicle : public FactGroup MavCmdResultFailureDuplicateCommand, ///< Unable to send command since duplicate is already being waited on for response } MavCmdResultFailureCode_t; - /// Callback for sendMavCommandWithHandler - /// @param resultHandleData Opaque data passed in to sendMavCommand call - /// @param commandResult Ack result for command send - /// @param failureCode Failure reason - typedef void (*MavCmdResultHandler)(void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, MavCmdResultFailureCode_t failureCode); + /// Callback for sendMavCommandWithHandler which handles MAV_RESULT_IN_PROGRESS acks + /// @param progressHandlerData Opaque data passed in to sendMavCommand call + /// @param ack Received COMMAND_ACK + typedef void (*MavCmdProgressHandler)(void* progressHandlerData, int compId, const mavlink_command_ack_t& ack); + + /// Callback for sendMavCommandWithHandler which handles all acks which are not MAV_RESULT_IN_PROGRESS + /// @param resultHandlerData Opaque data passed in to sendMavCommand call + /// @param ack Received COMMAND_ACK + /// @param failureCode Failure reason. If not MavCmdResultCommandResultOnly only ack.result == MAV_RESULT_FAILED is valid. + typedef void (*MavCmdResultHandler)(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode); + + // Callback info for sendMavCommandWithHandler + typedef struct MavCmdAckHandlerInfo_s { + MavCmdResultHandler resultHandler; ///> nullptr for no handler + void* resultHandlerData; + MavCmdProgressHandler progressHandler; + void* progressHandlerData; ///> nullptr for no handler + } MavCmdAckHandlerInfo_t; /// Sends the command and calls the callback with the result - /// @param resultHandler Callback for result, nullptr for no callback - /// @param resultHandleData Opaque data passed through callback - void sendMavCommandWithHandler(MavCmdResultHandler resultHandler, void* resultHandlerData, int compId, MAV_CMD command, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f); + void sendMavCommandWithHandler( + const MavCmdAckHandlerInfo_t* ackHandlerInfo, ///> nullptr to signale no handlers + int compId, MAV_CMD command, + float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f); /// Sends the command and calls the callback with the result /// @param resultHandler Callback for result, nullptr for no callback /// @param resultHandleData Opaque data passed through callback - void sendMavCommandIntWithHandler(MavCmdResultHandler resultHandler, void* resultHandlerData, int compId, MAV_CMD command, MAV_FRAME frame, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, double param5 = 0.0f, double param6 = 0.0f, float param7 = 0.0f); + void sendMavCommandIntWithHandler( + const MavCmdAckHandlerInfo_t* ackHandlerInfo, ///> nullptr to signale no handlers + int compId, MAV_CMD command, MAV_FRAME frame, + float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, double param5 = 0.0f, double param6 = 0.0f, float param7 = 0.0f); typedef enum { RequestMessageNoFailure, @@ -1095,7 +1112,7 @@ private slots: EventHandler& _eventHandler (uint8_t compid); bool setFlightModeCustom (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode); - static void _rebootCommandResultHandler(void* resultHandlerData, int compId, MAV_RESULT commandResult, uint8_t progress, MavCmdResultFailureCode_t failureCode); + static void _rebootCommandResultHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode); // This is called after we get terrain data triggered from a doSetHome() void _doSetHomeTerrainReceived (bool success, QList heights); @@ -1309,28 +1326,27 @@ private slots: mavlink_message_t message; } RequestMessageInfo_t; - static void _requestMessageCmdResultHandler (void* resultHandlerData, int compId, MAV_RESULT result, uint8_t progress, MavCmdResultFailureCode_t failureCode); + static void _requestMessageCmdResultHandler (void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode); static void _requestMessageWaitForMessageResultHandler (void* resultHandlerData, bool noResponsefromVehicle, const mavlink_message_t& message); typedef struct MavCommandListEntry { - int targetCompId = MAV_COMP_ID_AUTOPILOT1; - bool useCommandInt = false; - MAV_CMD command; - MAV_FRAME frame; - float rgParam1 = 0; - float rgParam2 = 0; - float rgParam3 = 0; - float rgParam4 = 0; - double rgParam5 = 0; - double rgParam6 = 0; - float rgParam7 = 0; - bool showError = true; - MavCmdResultHandler resultHandler; - void* resultHandlerData = nullptr; - int maxTries = _mavCommandMaxRetryCount; - int tryCount = 0; - QElapsedTimer elapsedTimer; - int ackTimeoutMSecs = _mavCommandAckTimeoutMSecs; + int targetCompId = MAV_COMP_ID_AUTOPILOT1; + bool useCommandInt = false; + MAV_CMD command; + MAV_FRAME frame; + float rgParam1 = 0; + float rgParam2 = 0; + float rgParam3 = 0; + float rgParam4 = 0; + double rgParam5 = 0; + double rgParam6 = 0; + float rgParam7 = 0; + bool showError = true; + MavCmdAckHandlerInfo_t ackHandlerInfo; + int maxTries = _mavCommandMaxRetryCount; + int tryCount = 0; + QElapsedTimer elapsedTimer; + int ackTimeoutMSecs = _mavCommandAckTimeoutMSecs; } MavCommandListEntry_t; QList _mavCommandList; @@ -1340,7 +1356,11 @@ private slots: static const int _mavCommandAckTimeoutMSecs = 3000; static const int _mavCommandAckTimeoutMSecsHighLatency = 120000; - void _sendMavCommandWorker (bool commandInt, bool showError, MavCmdResultHandler resultHandler, void* resultHandlerData, int compId, MAV_CMD command, MAV_FRAME frame, float param1, float param2, float param3, float param4, double param5, double param6, float param7); + void _sendMavCommandWorker ( + bool commandInt, bool showError, + const MavCmdAckHandlerInfo_t* ackHandlerInfo, ///> nullptr to signale no handlers + int compId, MAV_CMD command, MAV_FRAME frame, + float param1, float param2, float param3, float param4, double param5, double param6, float param7); void _sendMavCommandFromList(int index); int _findMavCommandListEntryIndex(int targetCompId, MAV_CMD command); bool _sendMavCommandShouldRetry(MAV_CMD command); diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index bd264e3f471..025662fe9cc 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -55,6 +55,9 @@ constexpr MAV_CMD MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_ACCEPTED; constexpr MAV_CMD MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED; constexpr MAV_CMD MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE; constexpr MAV_CMD MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE_NO_RETRY; +constexpr MAV_CMD MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_ACCEPTED; +constexpr MAV_CMD MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_FAILED; +constexpr MAV_CMD MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_NO_ACK; // The LinkManager is only forward declared in the header, so a static_assert is here instead to ensure we update if the value changes. static_assert(LinkManager::invalidMavlinkChannel() == std::numeric_limits::max(), "update MockLink::_mavlinkAuxChannel"); @@ -1052,6 +1055,53 @@ void MockLink::_handleFTP(const mavlink_message_t& msg) _mockLinkFTP->mavlinkMessageReceived(msg); } +void MockLink::_handleInProgressCommandLong(const mavlink_command_long_t& request) +{ + uint8_t commandResult = MAV_RESULT_UNSUPPORTED; + + switch (request.command) { + case MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_ACCEPTED: + // Test command which sends in progress messages and then acceptance ack + commandResult = MAV_RESULT_ACCEPTED; + break; + case MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_FAILED: + // Test command which sends in progress messages and then failure ack + commandResult = MAV_RESULT_FAILED; + break; + case MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_NO_ACK: + // Test command which sends in progress messages and then never sends final result ack + break; + } + + mavlink_message_t commandAck; + + mavlink_msg_command_ack_pack_chan(_vehicleSystemId, + _vehicleComponentId, + mavlinkChannel(), + &commandAck, + request.command, + MAV_RESULT_IN_PROGRESS, + 1, // progress + 0, // result_param2 + 0, // target_system + 0); // target_component + respondWithMavlinkMessage(commandAck); + + if (request.command != MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_NO_ACK) { + mavlink_msg_command_ack_pack_chan(_vehicleSystemId, + _vehicleComponentId, + mavlinkChannel(), + &commandAck, + request.command, + commandResult, + 0, // progress + 0, // result_param2 + 0, // target_system + 0); // target_component + respondWithMavlinkMessage(commandAck); + } +} + void MockLink::_handleCommandLong(const mavlink_message_t& msg) { static bool firstCmdUser3 = true; @@ -1063,7 +1113,7 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg) mavlink_msg_command_long_decode(&msg, &request); - _sendMavCommandCountMap[static_cast(request.command)]++; + _receivedMavCommandCountMap[static_cast(request.command)]++; switch (request.command) { case MAV_CMD_COMPONENT_ARM_DISARM: @@ -1111,7 +1161,7 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg) commandResult = MAV_RESULT_FAILED; break; case MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_ACCEPTED: - // Test command which returns MAV_RESULT_ACCEPTED on second attempt + // Test command which does not respond to first request and returns MAV_RESULT_ACCEPTED on second attempt if (firstCmdUser3) { firstCmdUser3 = false; return; @@ -1121,7 +1171,7 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg) } break; case MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED: - // Test command which returns MAV_RESULT_FAILED on second attempt + // Test command which does not respond to first request and returns MAV_RESULT_FAILED on second attempt if (firstCmdUser4) { firstCmdUser4 = false; return; @@ -1132,7 +1182,12 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg) break; case MAV_CMD_MOCKLINK_NO_RESPONSE: case MAV_CMD_MOCKLINK_NO_RESPONSE_NO_RETRY: - // No response + // Test command which never responds + return; + case MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_ACCEPTED: + case MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_FAILED: + case MockLink::MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_NO_ACK: + _handleInProgressCommandLong(request); return; } diff --git a/src/comm/MockLink.h b/src/comm/MockLink.h index d1b4e64ae23..dca13e91373 100644 --- a/src/comm/MockLink.h +++ b/src/comm/MockLink.h @@ -162,16 +162,19 @@ class MockLink : public LinkInterface static MockLink* startAPMArduSubMockLink (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone); static MockLink* startAPMArduRoverMockLink (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone); - // Special commands for testing COMMAND_LONG handlers. By default all commands except for MAV_CMD_MOCKLINK_NO_RESPONSE_NO_RETRY should retry. + // Special commands for testing Vehicle::sendMavCommandWithHandler static constexpr MAV_CMD MAV_CMD_MOCKLINK_ALWAYS_RESULT_ACCEPTED = MAV_CMD_USER_1; static constexpr MAV_CMD MAV_CMD_MOCKLINK_ALWAYS_RESULT_FAILED = MAV_CMD_USER_2; static constexpr MAV_CMD MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_ACCEPTED = MAV_CMD_USER_3; static constexpr MAV_CMD MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED = MAV_CMD_USER_4; static constexpr MAV_CMD MAV_CMD_MOCKLINK_NO_RESPONSE = MAV_CMD_USER_5; static constexpr MAV_CMD MAV_CMD_MOCKLINK_NO_RESPONSE_NO_RETRY = static_cast(MAV_CMD_USER_5 + 1); + static constexpr MAV_CMD MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_ACCEPTED = static_cast(MAV_CMD_USER_5 + 2); + static constexpr MAV_CMD MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_FAILED = static_cast(MAV_CMD_USER_5 + 3); + static constexpr MAV_CMD MAV_CMD_MOCKLINK_RESULT_IN_PROGRESS_NO_ACK = static_cast(MAV_CMD_USER_5 + 4); - void clearSendMavCommandCounts(void) { _sendMavCommandCountMap.clear(); } - int sendMavCommandCount(MAV_CMD command) { return _sendMavCommandCountMap[command]; } + void clearReceivedMavCommandCounts(void) { _receivedMavCommandCountMap.clear(); } + int receivedMavCommandCount(MAV_CMD command) { return _receivedMavCommandCountMap[command]; } typedef enum { FailRequestMessageNone, @@ -220,6 +223,7 @@ private slots: void _handleParamRequestRead (const mavlink_message_t& msg); void _handleFTP (const mavlink_message_t& msg); void _handleCommandLong (const mavlink_message_t& msg); + void _handleInProgressCommandLong (const mavlink_command_long_t& request); void _handleManualControl (const mavlink_message_t& msg); void _handlePreFlightCalibration (const mavlink_command_long_t& request); void _handleLogRequestList (const mavlink_message_t& msg); @@ -310,7 +314,7 @@ private slots: RequestMessageFailureMode_t _requestMessageFailureMode = FailRequestMessageNone; - QMap _sendMavCommandCountMap; + QMap _receivedMavCommandCountMap; QMap> _mapParamName2Value; QMap> _mapParamName2MavParamType; From 2f9b78d6c3b469a55fa01a270cf933e1b5166d60 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 14 Nov 2023 09:31:16 -0800 Subject: [PATCH 107/118] Hack for PX4 auto-tune --- src/Vehicle/Vehicle.cc | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 5962b4b2b24..570e3ab6935 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3277,7 +3277,13 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message) int entryIndex = _findMavCommandListEntryIndex(message.compid, static_cast(ack.command)); if (entryIndex != -1) { if (ack.result == MAV_RESULT_IN_PROGRESS) { - MavCommandListEntry_t commandEntry = _mavCommandList.at(entryIndex); // Command has not completed yet, don't remove + MavCommandListEntry_t commandEntry; + if (px4Firmware() && ack.command == MAV_CMD_DO_AUTOTUNE_ENABLE) { + // HacK to support PX4 autotune which does not send final result ack and just sends in progress + commandEntry = _mavCommandList.takeAt(entryIndex); + } else { + commandEntry = _mavCommandList.at(entryIndex); // Command has not completed yet, don't remove + } commandEntry.maxTries = 1; // Vehicle responsed to command so don't retry commandEntry.elapsedTimer.restart(); // We've heard from vehicle, restart elapsed timer for no ack received timeout From 7e020440cc28c3b6b19a2d5463b8f256fdf687c7 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Fri, 17 Nov 2023 10:06:41 +0000 Subject: [PATCH 108/118] Update PX4 Firmware metadata Fri Nov 17 10:06:41 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index d496b9c682f..9424f89e61f 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -1033,6 +1033,10 @@ 1 0.1 + + Allow disarming via switch/stick/button on multicopters in manual thrust modes + 0: Disallow disarming when not landed 1: Allow disarming in multicopter flight in modes where the thrust is directly controlled by thr throttle stick e.g. Stabilized, Acro + Time-out for auto disarm if not taking off A non-zero, positive value specifies the time in seconds, within which the vehicle is expected to take off after arming. In case the vehicle didn't takeoff within the timeout it disarms again. A negative value disables autmoatic disarming triggered by a pre-takeoff timeout. @@ -4519,6 +4523,14 @@ Enable arm/disarm stick gesture This determines if moving the left stick to the lower right arms and to the lower left disarms the vehicle. + + Trigger time for kill stick gesture + The timeout for holding the left stick to the lower left and the right stick to the lower right at the same time until the gesture kills the actuators one-way. A negative value disables the feature. + -1 + 15 + s + 2 + From 3733318c93981d4da2bf37225d691a4cbc37fc39 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Mon, 19 Jun 2023 19:19:51 +0200 Subject: [PATCH 109/118] Ardupilot: Add support for fixed wing airspeed change --- src/FirmwarePlugin/APM/APMFirmwarePlugin.cc | 42 +++++++++++++++++++++ src/FirmwarePlugin/APM/APMFirmwarePlugin.h | 4 ++ 2 files changed, 46 insertions(+) diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 987826a2a6e..58cd5a070f6 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -1133,3 +1133,45 @@ QMutex& APMFirmwarePlugin::_reencodeMavlinkChannelMutex() static QMutex _mutex{}; return _mutex; } + +double APMFirmwarePlugin::maximumEquivalentAirspeed(Vehicle* vehicle) +{ + QString airspeedMax("ARSPD_FBW_MAX"); + + if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, airspeedMax)) { + return vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, airspeedMax)->rawValue().toDouble(); + } + + return FirmwarePlugin::maximumEquivalentAirspeed(vehicle); +} + +double APMFirmwarePlugin::minimumEquivalentAirspeed(Vehicle* vehicle) +{ + QString airspeedMin("ARSPD_FBW_MIN"); + + if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, airspeedMin)) { + return vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, airspeedMin)->rawValue().toDouble(); + } + + return FirmwarePlugin::minimumEquivalentAirspeed(vehicle); +} + +bool APMFirmwarePlugin::fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle) +{ + return vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "ARSPD_FBW_MIN") && + vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "ARSPD_FBW_MAX"); +} + +void APMFirmwarePlugin::guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv) +{ + + vehicle->sendMavCommand( + vehicle->defaultComponentId(), + MAV_CMD_DO_CHANGE_SPEED, + true, // show error is fails + 0, // 0: airspeed, 1: groundspeed + static_cast(airspeed_equiv), // speed setpoint + -1, // throttle, no change + 0 // 0: absolute speed, 1: relative to current + ); // param 5-7 unused +} \ No newline at end of file diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index 4a1dd068673..4dd3d2f1922 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -80,6 +80,10 @@ class APMFirmwarePlugin : public FirmwarePlugin QString getHobbsMeter (Vehicle* vehicle) override; bool hasGripper (const Vehicle* vehicle) const override; const QVariantList& toolIndicators (const Vehicle* vehicle) override; + double maximumEquivalentAirspeed (Vehicle* vehicle) override; + double minimumEquivalentAirspeed (Vehicle* vehicle) override; + bool fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle) override; + void guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv) override; protected: /// All access to singleton is through stack specific implementation From 4c1f6c751a0c28f00219f9c1b1f070b932467d43 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Tue, 18 Jul 2023 17:44:18 +0200 Subject: [PATCH 110/118] FactMetadata, QmlUnitsConversion: support for speed unit translation --- src/FactSystem/FactMetaData.cc | 20 ++++++++++++++++++++ src/FactSystem/FactMetaData.h | 6 ++++++ src/QmlControls/QmlUnitsConversion.h | 6 ++++++ 3 files changed, 32 insertions(+) diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc index e8d8dfa5efd..b92defe4724 100644 --- a/src/FactSystem/FactMetaData.cc +++ b/src/FactSystem/FactMetaData.cc @@ -1200,6 +1200,26 @@ QVariant FactMetaData::appSettingsWeightUnitsToGrams(const QVariant& weight) { } } +QVariant FactMetaData::metersSecondToAppSettingsSpeedUnits(const QVariant& metersSecond) +{ + const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsUnitsTranslation("m/s", UnitSpeed); + if (pAppSettingsTranslation) { + return pAppSettingsTranslation->rawTranslator(metersSecond); + } else { + return metersSecond; + } +} + +QVariant FactMetaData::appSettingsSpeedUnitsToMetersSecond(const QVariant& speed) +{ + const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsUnitsTranslation("m/s", UnitSpeed); + if (pAppSettingsTranslation) { + return pAppSettingsTranslation->cookedTranslator(speed); + } else { + return speed; + } +} + QString FactMetaData::appSettingsSpeedUnitsString() { const AppSettingsTranslation_s* pAppSettingsTranslation = _findAppSettingsUnitsTranslation("m/s", UnitSpeed); diff --git a/src/FactSystem/FactMetaData.h b/src/FactSystem/FactMetaData.h index 6b12bc2df79..06145cce568 100644 --- a/src/FactSystem/FactMetaData.h +++ b/src/FactSystem/FactMetaData.h @@ -99,6 +99,12 @@ class FactMetaData : public QObject /// Returns the string for distance units which has configued by user static QString appSettingsAreaUnitsString(void); + /// Converts from meters/second to the user specified speed unit + static QVariant metersSecondToAppSettingsSpeedUnits(const QVariant& metersSecond); + + /// Converts from user specified speed unit to meters/second + static QVariant appSettingsSpeedUnitsToMetersSecond(const QVariant& speed); + /// Returns the string for speed units which has configued by user static QString appSettingsSpeedUnitsString(); diff --git a/src/QmlControls/QmlUnitsConversion.h b/src/QmlControls/QmlUnitsConversion.h index 267503dc787..769018f6198 100644 --- a/src/QmlControls/QmlUnitsConversion.h +++ b/src/QmlControls/QmlUnitsConversion.h @@ -59,6 +59,12 @@ class QmlUnitsConversion : public QObject QString appSettingsAreaUnitsString(void) const { return FactMetaData::appSettingsAreaUnitsString(); } + /// Converts from meters/second to the user specified speed unit + Q_INVOKABLE QVariant metersSecondToAppSettingsSpeedUnits(const QVariant& metersSecond) const { return FactMetaData::metersSecondToAppSettingsSpeedUnits(metersSecond); } + + /// Converts from user specified speed unit to meters/second + Q_INVOKABLE QVariant appSettingsSpeedUnitsToMetersSecond(const QVariant& speed) const { return FactMetaData::appSettingsSpeedUnitsToMetersSecond(speed); } + /// Returns the string for speed units which has configued by user QString appSettingsSpeedUnitsString() { return FactMetaData::appSettingsSpeedUnitsString(); } From 8bffc3fbd6671db771c933add4bd39b4e326f2f2 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Mon, 19 Jun 2023 19:20:09 +0200 Subject: [PATCH 111/118] Fix altitude slider and guidedactions for speed action: There were some errors where fixed wing would not show the action, also unit conversion support for speed was added --- src/FlightDisplay/GuidedActionsController.qml | 24 +++++++++++-------- src/FlightDisplay/GuidedValueSlider.qml | 15 ++++++++++-- 2 files changed, 27 insertions(+), 12 deletions(-) diff --git a/src/FlightDisplay/GuidedActionsController.qml b/src/FlightDisplay/GuidedActionsController.qml index f6ce0e28dfd..b434567f5b0 100644 --- a/src/FlightDisplay/GuidedActionsController.qml +++ b/src/FlightDisplay/GuidedActionsController.qml @@ -190,22 +190,24 @@ Item { function setupSlider(actionCode) { // generic defaults guidedValueSlider.configureAsLinearSlider() + guidedValueSlider.setIsSpeedSlider(false) if (actionCode === actionTakeoff) { guidedValueSlider.setMinVal(_activeVehicle.minimumTakeoffAltitude()) guidedValueSlider.setValue(_activeVehicle ? _activeVehicle.minimumTakeoffAltitude() : 0) guidedValueSlider.setDisplayText("Height") } else if (actionCode === actionChangeSpeed) { - if (_activeVehicle.vtolInFwdFlight) { + guidedValueSlider.setIsSpeedSlider(true) + if (_fixedWing) { guidedValueSlider.setDisplayText("Set Airspeed") - guidedValueSlider.setMinVal(_activeVehicle.minimumEquivalentAirspeed()) - guidedValueSlider.setMaxVal(_activeVehicle.maximumEquivalentAirspeed()) - guidedValueSlider.setValue(_activeVehicle.airSpeedSetpoint.rawValue) - } else { + guidedValueSlider.setMinVal(QGroundControl.unitsConversion.metersSecondToAppSettingsSpeedUnits(_activeVehicle.minimumEquivalentAirspeed()).toFixed(1)) + guidedValueSlider.setMaxVal(QGroundControl.unitsConversion.metersSecondToAppSettingsSpeedUnits(_activeVehicle.maximumEquivalentAirspeed()).toFixed(1)) + guidedValueSlider.setValue(_activeVehicle.airSpeed.value) + } else if (!_fixedWing && _activeVehicle.haveMRSpeedLimits) { guidedValueSlider.setDisplayText("Set Speed") - guidedValueSlider.setMinVal(0.1) - guidedValueSlider.setMaxVal(_activeVehicle.maximumHorizontalSpeedMultirotor()) - guidedValueSlider.setValue(_activeVehicle.maximumHorizontalSpeedMultirotor()/2) + guidedValueSlider.setMinVal(QGroundControl.unitsConversion.metersSecondToAppSettingsSpeedUnits(0.1).toFixed(1)) + guidedValueSlider.setMaxVal(QGroundControl.unitsConversion.metersSecondToAppSettingsSpeedUnits(_activeVehicle.maximumHorizontalSpeedMultirotor()).toFixed(1)) + guidedValueSlider.setValue(QGroundControl.unitsConversion.metersSecondToAppSettingsSpeedUnits(_activeVehicle.maximumHorizontalSpeedMultirotor()/2).toFixed(1)) } } else if (actionCode === actionChangeAlt || actionCode === actionOrbit || actionCode === actionGoto || actionCode === actionPause) { guidedValueSlider.setDisplayText("New Alt(rel)") @@ -599,10 +601,12 @@ Item { break case actionChangeSpeed: if (_activeVehicle) { + // We need to convert back to m/s as that is what mavlink standard uses for MAV_CMD_DO_CHANGE_SPEED + var metersSecondSpeed = QGroundControl.unitsConversion.appSettingsSpeedUnitsToMetersSecond(sliderOutputValue).toFixed(1) if (_activeVehicle.vtolInFwdFlight || _activeVehicle.fixedWing) { - _activeVehicle.guidedModeChangeEquivalentAirspeed(sliderOutputValue) + _activeVehicle.guidedModeChangeEquivalentAirspeed(metersSecondSpeed) } else { - _activeVehicle.guidedModeChangeGroundSpeed(sliderOutputValue) + _activeVehicle.guidedModeChangeGroundSpeed(metersSecondSpeed) } } break diff --git a/src/FlightDisplay/GuidedValueSlider.qml b/src/FlightDisplay/GuidedValueSlider.qml index 1548aecdeb1..a7487c613cb 100644 --- a/src/FlightDisplay/GuidedValueSlider.qml +++ b/src/FlightDisplay/GuidedValueSlider.qml @@ -26,6 +26,7 @@ Rectangle { property real _sliderCenterValue: _vehicleAltitude property string _displayText: "" property bool _altSlider: true + property bool _speedSlider: false property var sliderValue : valueSlider.value @@ -75,6 +76,10 @@ Rectangle { _displayText = text } + function setIsSpeedSlider(isSpeed) { + _speedSlider = isSpeed + } + function getOutputValue() { if (_altSlider) { return valueField.newValue - _sliderCenterValue @@ -101,7 +106,8 @@ Rectangle { QGCLabel { id: valueField anchors.horizontalCenter: parent.horizontalCenter - text: newValueAppUnits + " " + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString + text: newValueAppUnits + " " + (_speedSlider ? QGroundControl.unitsConversion.appSettingsSpeedUnitsString + : QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString) property real newValue property string newValueAppUnits @@ -120,7 +126,12 @@ Rectangle { function updateLinear(value) { // value is between -1 and 1 newValue = _sliderMinVal + (value + 1) * 0.5 * (_sliderMaxVal - _sliderMinVal) - newValueAppUnits = QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(newValue).toFixed(1) + if (_speedSlider) { + // Already working in converted units + newValueAppUnits = newValue.toFixed(1) + } else { + newValueAppUnits = QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(newValue).toFixed(1) + } } function getSliderValueFromOutputLinear(val) { From 4ff44aa82cfe807759c4fa88e9175e7aefc64192 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Tue, 18 Jul 2023 18:00:57 +0200 Subject: [PATCH 112/118] Change function name *changeSpeed to changeSpeedMetersSecond: Ultimately it sends a MAV_CMD_DO_CHANGE_SPEED in meters per second, so it is clearer if we have this name for the function, could help avoiding confusion in the future --- src/FirmwarePlugin/APM/APMFirmwarePlugin.cc | 2 +- src/FirmwarePlugin/APM/APMFirmwarePlugin.h | 2 +- src/FirmwarePlugin/FirmwarePlugin.cc | 4 ++-- src/FirmwarePlugin/FirmwarePlugin.h | 4 ++-- src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc | 4 ++-- src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h | 4 ++-- src/FlightDisplay/GuidedActionsController.qml | 4 ++-- src/Vehicle/Vehicle.cc | 8 ++++---- src/Vehicle/Vehicle.h | 4 ++-- 9 files changed, 18 insertions(+), 18 deletions(-) diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 58cd5a070f6..4e0fdefe14c 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -1162,7 +1162,7 @@ bool APMFirmwarePlugin::fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle) vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "ARSPD_FBW_MAX"); } -void APMFirmwarePlugin::guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv) +void APMFirmwarePlugin::guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle* vehicle, double airspeed_equiv) { vehicle->sendMavCommand( diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index 4dd3d2f1922..1530de15258 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -83,7 +83,7 @@ class APMFirmwarePlugin : public FirmwarePlugin double maximumEquivalentAirspeed (Vehicle* vehicle) override; double minimumEquivalentAirspeed (Vehicle* vehicle) override; bool fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle) override; - void guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv) override; + void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle* vehicle, double airspeed_equiv) override; protected: /// All access to singleton is through stack specific implementation diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 35d44b23492..32cd3a6af86 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -276,14 +276,14 @@ void FirmwarePlugin::guidedModeChangeAltitude(Vehicle*, double, bool pauseVehicl } void -FirmwarePlugin::guidedModeChangeGroundSpeed(Vehicle*, double) +FirmwarePlugin::guidedModeChangeGroundSpeedMetersSecond(Vehicle*, double) { // Not supported by generic vehicle qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); } void -FirmwarePlugin::guidedModeChangeEquivalentAirspeed(Vehicle*, double) +FirmwarePlugin::guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle*, double) { // Not supported by generic vehicle qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index f4f05a0139d..f9444b4eea3 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -180,11 +180,11 @@ class FirmwarePlugin : public QObject /// Command vehicle to change groundspeed /// @param groundspeed Groundspeed in m/s - virtual void guidedModeChangeGroundSpeed(Vehicle* vehicle, double groundspeed); + virtual void guidedModeChangeGroundSpeedMetersSecond(Vehicle* vehicle, double groundspeed); /// Command vehicle to change equivalent airspeed /// @param airspeed_equiv Equivalent airspeed in m/s - virtual void guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv); + virtual void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle* vehicle, double airspeed_equiv); /// Default tx mode to apply to joystick axes /// TX modes are as outlined here: http://www.rc-airplane-world.com/rc-transmitter-modes.html diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index b8fab2716ff..cf76d12af23 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -572,7 +572,7 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu } } -void PX4FirmwarePlugin::guidedModeChangeGroundSpeed(Vehicle* vehicle, double groundspeed) +void PX4FirmwarePlugin::guidedModeChangeGroundSpeedMetersSecond(Vehicle* vehicle, double groundspeed) { vehicle->sendMavCommand( @@ -586,7 +586,7 @@ void PX4FirmwarePlugin::guidedModeChangeGroundSpeed(Vehicle* vehicle, double gro NAN, NAN,NAN); // param 5-7 unused } -void PX4FirmwarePlugin::guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv) +void PX4FirmwarePlugin::guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle* vehicle, double airspeed_equiv) { vehicle->sendMavCommand( diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index ff8e9eb8c02..a0a8d62ad48 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -53,8 +53,8 @@ class PX4FirmwarePlugin : public FirmwarePlugin bool fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle) override; void guidedModeGotoLocation (Vehicle* vehicle, const QGeoCoordinate& gotoCoord) override; void guidedModeChangeAltitude (Vehicle* vehicle, double altitudeRel, bool pauseVehicle) override; - void guidedModeChangeGroundSpeed (Vehicle* vehicle, double groundspeed) override; - void guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv) override; + void guidedModeChangeGroundSpeedMetersSecond(Vehicle* vehicle, double groundspeed) override; + void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle* vehicle, double airspeed_equiv) override; void startMission (Vehicle* vehicle) override; bool isGuidedMode (const Vehicle* vehicle) const override; void initializeVehicle (Vehicle* vehicle) override; diff --git a/src/FlightDisplay/GuidedActionsController.qml b/src/FlightDisplay/GuidedActionsController.qml index b434567f5b0..26985353cb2 100644 --- a/src/FlightDisplay/GuidedActionsController.qml +++ b/src/FlightDisplay/GuidedActionsController.qml @@ -604,9 +604,9 @@ Item { // We need to convert back to m/s as that is what mavlink standard uses for MAV_CMD_DO_CHANGE_SPEED var metersSecondSpeed = QGroundControl.unitsConversion.appSettingsSpeedUnitsToMetersSecond(sliderOutputValue).toFixed(1) if (_activeVehicle.vtolInFwdFlight || _activeVehicle.fixedWing) { - _activeVehicle.guidedModeChangeEquivalentAirspeed(metersSecondSpeed) + _activeVehicle.guidedModeChangeEquivalentAirspeedMetersSecond(metersSecondSpeed) } else { - _activeVehicle.guidedModeChangeGroundSpeed(metersSecondSpeed) + _activeVehicle.guidedModeChangeGroundSpeedMetersSecond(metersSecondSpeed) } } break diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 570e3ab6935..b486f06fa5d 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -2775,23 +2775,23 @@ void Vehicle::guidedModeChangeAltitude(double altitudeChange, bool pauseVehicle) } void -Vehicle::guidedModeChangeGroundSpeed(double groundspeed) +Vehicle::guidedModeChangeGroundSpeedMetersSecond(double groundspeed) { if (!guidedModeSupported()) { qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); return; } - _firmwarePlugin->guidedModeChangeGroundSpeed(this, groundspeed); + _firmwarePlugin->guidedModeChangeGroundSpeedMetersSecond(this, groundspeed); } void -Vehicle::guidedModeChangeEquivalentAirspeed(double airspeed) +Vehicle::guidedModeChangeEquivalentAirspeedMetersSecond(double airspeed) { if (!guidedModeSupported()) { qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle); return; } - _firmwarePlugin->guidedModeChangeEquivalentAirspeed(this, airspeed); + _firmwarePlugin->guidedModeChangeEquivalentAirspeedMetersSecond(this, airspeed); } void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude) diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 5a61c786aa6..6440908a08a 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -378,10 +378,10 @@ class Vehicle : public FactGroup /// Command vehicle to change groundspeed /// @param groundspeed Target horizontal groundspeed - Q_INVOKABLE void guidedModeChangeGroundSpeed (double groundspeed); + Q_INVOKABLE void guidedModeChangeGroundSpeedMetersSecond(double groundspeed); /// Command vehicle to change equivalent airspeed /// @param airspeed Target equivalent airspeed - Q_INVOKABLE void guidedModeChangeEquivalentAirspeed (double airspeed); + Q_INVOKABLE void guidedModeChangeEquivalentAirspeedMetersSecond(double airspeed); /// Command vehicle to orbit given center point /// @param centerCoord Orit around this point From 1624783c5d25c544293a736d7424b18539e2a4d5 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 31 Oct 2023 21:03:38 +0000 Subject: [PATCH 113/118] Fix setup of ANDROID_PACKAGE_SOURCE_DIR Remove double call to make Specify androiddeployqt location Revert "Specify androiddeployqt location" This reverts commit cc307cf32f0e9040aa8256d8b2799f8ff9168b9c. Revert "Remove double call to make" This reverts commit 3fee0e92fc537bee6586f674b8bf58463f0257da. Remove PRE_TARGETDEPS Fix target dependency to prevent make loop --- android.pri | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/android.pri b/android.pri index 641121f553e..43dbbf9bf08 100644 --- a/android.pri +++ b/android.pri @@ -8,20 +8,23 @@ ANDROID_PACKAGE_CUSTOM_SOURCE_DIR = $$PWD/custom/android # Or # We always move the package files to the ANDROID_PACKAGE_SOURCE_DIR build dir so we can modify the manifest as needed -android_source_dir_target.target = $$ANDROID_PACKAGE_QGC_SOURCE_DIR/AndroidManifest.xml +android_source_dir_target.target = $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml android_source_dir_target.commands = \ $$QMAKE_MKDIR $$ANDROID_PACKAGE_SOURCE_DIR && \ $$QMAKE_COPY_DIR $$ANDROID_PACKAGE_QGC_SOURCE_DIR/* $$ANDROID_PACKAGE_SOURCE_DIR PRE_TARGETDEPS += $$android_source_dir_target.target QMAKE_EXTRA_TARGETS += android_source_dir_target -android_source_dir_target.depends = FORCE +exists($$ANDROID_PACKAGE_CUSTOM_SOURCE_DIR/AndroidManifest.xml) { + android_source_dir_target.depends = $$ANDROID_PACKAGE_CUSTOM_SOURCE_DIR/AndroidManifest.xml +} else { + android_source_dir_target.depends = $$ANDROID_PACKAGE_QGC_SOURCE_DIR/AndroidManifest.xml +} # Custom builds can override android package file exists($$ANDROID_PACKAGE_CUSTOM_SOURCE_DIR) { message("Merging$$ $$ANDROID_PACKAGE_QGC_SOURCE_DIR and $$ANDROID_PACKAGE_CUSTOM_SOURCE_DIR to $$ANDROID_PACKAGE_SOURCE_DIR") - android_source_dir_target.target = $$ANDROID_PACKAGE_CUSTOM_SOURCE_DIR/AndroidManifest.xml android_source_dir_target.commands = $$android_source_dir_target.commands && \ $$QMAKE_COPY_DIR $$ANDROID_PACKAGE_CUSTOM_SOURCE_DIR/* $$ANDROID_PACKAGE_SOURCE_DIR && \ $$QMAKE_STREAM_EDITOR -i \"s/package=\\\"org.mavlink.qgroundcontrol\\\"/package=\\\"$$QGC_ANDROID_PACKAGE\\\"/\" $$ANDROID_PACKAGE_SOURCE_DIR/AndroidManifest.xml From e20a6f7fa8043797418049ad86a3466790c6b683 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Thu, 16 Nov 2023 23:59:24 +0100 Subject: [PATCH 114/118] Vehicle, qgroundcontrol.pro/qrc: Add support for EFI, and Generator factGroups --- qgroundcontrol.pro | 4 + qgroundcontrol.qrc | 2 + src/Vehicle/EFIFact.json | 122 +++++++++++++++++++++++ src/Vehicle/GeneratorFact.json | 77 ++++++++++++++ src/Vehicle/Vehicle.cc | 6 ++ src/Vehicle/Vehicle.h | 10 ++ src/Vehicle/VehicleEFIFactGroup.cc | 114 +++++++++++++++++++++ src/Vehicle/VehicleEFIFactGroup.h | 94 +++++++++++++++++ src/Vehicle/VehicleGeneratorFactGroup.cc | 110 ++++++++++++++++++++ src/Vehicle/VehicleGeneratorFactGroup.h | 75 ++++++++++++++ 10 files changed, 614 insertions(+) create mode 100644 src/Vehicle/EFIFact.json create mode 100644 src/Vehicle/GeneratorFact.json create mode 100644 src/Vehicle/VehicleEFIFactGroup.cc create mode 100644 src/Vehicle/VehicleEFIFactGroup.h create mode 100644 src/Vehicle/VehicleGeneratorFactGroup.cc create mode 100644 src/Vehicle/VehicleGeneratorFactGroup.h diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 5de21a05c3a..dc552482c63 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -745,6 +745,8 @@ HEADERS += \ src/Vehicle/VehicleVibrationFactGroup.h \ src/Vehicle/VehicleWindFactGroup.h \ src/Vehicle/VehicleHygrometerFactGroup.h \ + src/Vehicle/VehicleGeneratorFactGroup.h \ + src/Vehicle/VehicleEFIFactGroup.h \ src/VehicleSetup/JoystickConfigController.h \ src/comm/LinkConfiguration.h \ src/comm/LinkInterface.h \ @@ -1000,6 +1002,8 @@ SOURCES += \ src/Vehicle/VehicleTemperatureFactGroup.cc \ src/Vehicle/VehicleVibrationFactGroup.cc \ src/Vehicle/VehicleHygrometerFactGroup.cc \ + src/Vehicle/VehicleGeneratorFactGroup.cc \ + src/Vehicle/VehicleEFIFactGroup.cc \ src/Vehicle/VehicleWindFactGroup.cc \ src/VehicleSetup/JoystickConfigController.cc \ src/comm/LinkConfiguration.cc \ diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 5877af05917..99940a5b094 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -347,6 +347,8 @@ src/Vehicle/VibrationFact.json src/Vehicle/WindFact.json src/Vehicle/HygrometerFact.json + src/Vehicle/GeneratorFact.json + src/Vehicle/EFIFact.json src/Settings/Video.SettingsGroup.json src/MissionManager/VTOLLandingPattern.FactMetaData.json diff --git a/src/Vehicle/EFIFact.json b/src/Vehicle/EFIFact.json new file mode 100644 index 00000000000..e7c7f3d3a56 --- /dev/null +++ b/src/Vehicle/EFIFact.json @@ -0,0 +1,122 @@ +{ + "version": 1, + "fileType": "FactMetaData", + "QGC.MetaData.Facts": +[ +{ + "name": "health", + "shortDesc": "Health", + "type": "int8" +}, +{ + "name": "ecuIndex", + "shortDesc": "Ecu Index", + "type": "float", + "decimalPlaces": 1, + "units": "A" +}, +{ + "name": "rpm", + "shortDesc": "Rpm", + "type": "float", + "decimalPlaces": 1 +}, +{ + "name": "fuelConsumed", + "shortDesc": "Fuel Consumed", + "type": "float", + "decimalPlaces": 1, + "units": "cm^3" +}, +{ + "name": "fuelFlow", + "shortDesc": "Fuel Flow", + "type": "float", + "decimalPlaces": 1, + "units": "cm^3/min" +}, +{ + "name": "engineLoad", + "shortDesc": "Engine Load", + "type": "float", + "decimalPlaces": 1, + "units": "%" +}, +{ + "name": "throttlePos", + "shortDesc": "Throttle Position", + "type": "float", + "decimalPlaces": 1, + "units": "%" +}, +{ + "name": "sparkTime", + "shortDesc": "Spark dwell time", + "type": "float", + "decimalPlaces": 1, + "units": "ms" +}, +{ + "name": "baroPress", + "shortDesc": "BarometricPressure", + "type": "float", + "decimalPlaces": 1, + "units": "kPa" +}, +{ + "name": "intakePress", + "shortDesc": "Intake mainfold pressure", + "type": "float", + "decimalPlaces": 1, + "units": "kPa" +}, +{ + "name": "intakeTemp", + "shortDesc": "Intake mainfold temperature", + "type": "float", + "decimalPlaces": 1, + "units": "°C" +}, +{ + "name": "cylinderTemp", + "shortDesc": "Cylinder head temperature", + "type": "float", + "decimalPlaces": 1, + "units": "°C" +}, +{ + "name": "ignTime", + "shortDesc": "Ignition Timing", + "type": "float", + "decimalPlaces": 1, + "units": "deg" +}, +{ + "name": "injTime", + "shortDesc": "Injection Time", + "type": "float", + "decimalPlaces": 1, + "units": "ms" +}, +{ + "name": "exGasTemp", + "shortDesc": "Exhaust gas Temperature", + "type": "float", + "decimalPlaces": 1, + "units": "°C" +}, +{ + "name": "throttleOut", + "shortDesc": "Throttle Out", + "type": "float", + "decimalPlaces": 1, + "units": "%" +}, +{ + "name": "ptComp", + "shortDesc": "Pt Compensation", + "type": "float", + "decimalPlaces": 1 +} +] +} \ No newline at end of file diff --git a/src/Vehicle/GeneratorFact.json b/src/Vehicle/GeneratorFact.json new file mode 100644 index 00000000000..d5f8e6f68b5 --- /dev/null +++ b/src/Vehicle/GeneratorFact.json @@ -0,0 +1,77 @@ +{ + "version": 1, + "fileType": "FactMetaData", + "QGC.MetaData.Facts": +[ +{ + "name": "status", + "shortDesc": "Status", + "type": "uint64" +}, +{ + "name": "genSpeed", + "shortDesc": "Generator Speed", + "type": "uint16", + "units": "rpm" +}, +{ + "name": "batteryCurrent", + "shortDesc": "Battery Current", + "type": "float", + "decimalPlaces": 1, + "units": "A" +}, +{ + "name": "loadCurrent", + "shortDesc": "Load Current", + "type": "float", + "decimalPlaces": 1, + "units": "A" +}, +{ + "name": "powerGenerated", + "shortDesc": "Power Generated", + "type": "float", + "decimalPlaces": 1, + "units": "W" +}, +{ + "name": "busVoltage", + "shortDesc": "Bus Voltage", + "type": "float", + "decimalPlaces": 1, + "units": "V" +}, +{ + "name": "rectifierTemp", + "shortDesc": "Rectifier Temperature", + "type": "int16", + "units": "°C" +}, +{ + "name": "batCurrentSetpoint", + "shortDesc": "Battery Current Setpoint", + "type": "float", + "decimalPlaces": 1, + "units": "A" +}, +{ + "name": "genTemp", + "shortDesc": "Generator Temperature", + "type": "int16", + "units": "°C" +}, +{ + "name": "runtime", + "shortDesc": "runtime", + "type": "uint32", + "units": "sec" +}, +{ + "name": "timeMaintenance", + "shortDesc": "Time until Maintenance", + "type": "int32", + "units": "sec" +} +] +} \ No newline at end of file diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index b486f06fa5d..3b2874fbbe0 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -112,6 +112,8 @@ const char* Vehicle::_escStatusFactGroupName = "escStatus"; const char* Vehicle::_estimatorStatusFactGroupName = "estimatorStatus"; const char* Vehicle::_terrainFactGroupName = "terrain"; const char* Vehicle::_hygrometerFactGroupName = "hygrometer"; +const char* Vehicle::_generatorFactGroupName = "generator"; +const char* Vehicle::_efiFactGroupName = "efi"; // Standard connected vehicle Vehicle::Vehicle(LinkInterface* link, @@ -174,6 +176,8 @@ Vehicle::Vehicle(LinkInterface* link, , _escStatusFactGroup (this) , _estimatorStatusFactGroup (this) , _hygrometerFactGroup (this) + , _generatorFactGroup (this) + , _efiFactGroup (this) , _terrainFactGroup (this) , _terrainProtocolHandler (new TerrainProtocolHandler(this, &_terrainFactGroup, this)) { @@ -455,6 +459,8 @@ void Vehicle::_commonInit() _addFactGroup(&_escStatusFactGroup, _escStatusFactGroupName); _addFactGroup(&_estimatorStatusFactGroup, _estimatorStatusFactGroupName); _addFactGroup(&_hygrometerFactGroup, _hygrometerFactGroupName); + _addFactGroup(&_generatorFactGroup, _generatorFactGroupName); + _addFactGroup(&_efiFactGroup, _efiFactGroupName); _addFactGroup(&_terrainFactGroup, _terrainFactGroupName); // Add firmware-specific fact groups, if provided diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 6440908a08a..db2887dcf7a 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -49,6 +49,8 @@ #include "HealthAndArmingCheckReport.h" #include "TerrainQuery.h" #include "StandardModes.h" +#include "VehicleGeneratorFactGroup.h" +#include "VehicleEFIFactGroup.h" class Actuators; class EventHandler; @@ -322,6 +324,8 @@ class Vehicle : public FactGroup Q_PROPERTY(FactGroup* localPosition READ localPositionFactGroup CONSTANT) Q_PROPERTY(FactGroup* localPositionSetpoint READ localPositionSetpointFactGroup CONSTANT) Q_PROPERTY(FactGroup* hygrometer READ hygrometerFactGroup CONSTANT) + Q_PROPERTY(FactGroup* generator READ generatorFactGroup CONSTANT) + Q_PROPERTY(FactGroup* efi READ efiFactGroup CONSTANT) Q_PROPERTY(QmlObjectListModel* batteries READ batteries CONSTANT) Q_PROPERTY(Actuators* actuators READ actuators CONSTANT) Q_PROPERTY(HealthAndArmingCheckReport* healthAndArmingCheckReport READ healthAndArmingCheckReport CONSTANT) @@ -713,6 +717,8 @@ class Vehicle : public FactGroup FactGroup* estimatorStatusFactGroup () { return &_estimatorStatusFactGroup; } FactGroup* terrainFactGroup () { return &_terrainFactGroup; } FactGroup* hygrometerFactGroup () { return &_hygrometerFactGroup; } + FactGroup* generatorFactGroup () { return &_generatorFactGroup; } + FactGroup* efiFactGroup () { return &_efiFactGroup; } QmlObjectListModel* batteries () { return &_batteryFactGroupListModel; } MissionManager* missionManager () { return _missionManager; } @@ -1417,6 +1423,8 @@ private slots: VehicleEscStatusFactGroup _escStatusFactGroup; VehicleEstimatorStatusFactGroup _estimatorStatusFactGroup; VehicleHygrometerFactGroup _hygrometerFactGroup; + VehicleGeneratorFactGroup _generatorFactGroup; + VehicleEFIFactGroup _efiFactGroup; TerrainFactGroup _terrainFactGroup; QmlObjectListModel _batteryFactGroupListModel; @@ -1474,6 +1482,8 @@ private slots: static const char* _escStatusFactGroupName; static const char* _estimatorStatusFactGroupName; static const char* _hygrometerFactGroupName; + static const char* _generatorFactGroupName; + static const char* _efiFactGroupName; static const char* _terrainFactGroupName; static const int _vehicleUIUpdateRateMSecs = 100; diff --git a/src/Vehicle/VehicleEFIFactGroup.cc b/src/Vehicle/VehicleEFIFactGroup.cc new file mode 100644 index 00000000000..72d9b480fb1 --- /dev/null +++ b/src/Vehicle/VehicleEFIFactGroup.cc @@ -0,0 +1,114 @@ +#include "VehicleEFIFactGroup.h" +#include "Vehicle.h" + +const char* VehicleEFIFactGroup::_healthFactName = "health"; +const char* VehicleEFIFactGroup::_ecuIndexFactName = "ecuIndex"; +const char* VehicleEFIFactGroup::_rpmFactName = "rpm"; +const char* VehicleEFIFactGroup::_fuelConsumedFactName = "fuelConsumed"; +const char* VehicleEFIFactGroup::_fuelFlowFactName = "fuelFlow"; +const char* VehicleEFIFactGroup::_engineLoadFactName = "engineLoad"; +const char* VehicleEFIFactGroup::_throttlePosFactName = "throttlePos"; +const char* VehicleEFIFactGroup::_sparkTimeFactName = "sparkTime"; +const char* VehicleEFIFactGroup::_baroPressFactName = "baroPress"; +const char* VehicleEFIFactGroup::_intakePressFactName = "intakePress"; +const char* VehicleEFIFactGroup::_intakeTempFactName = "intakeTemp"; +const char* VehicleEFIFactGroup::_cylinderTempFactName = "cylinderTemp"; +const char* VehicleEFIFactGroup::_ignTimeFactName = "ignTime"; +const char* VehicleEFIFactGroup::_injTimeFactName = "injTime"; +const char* VehicleEFIFactGroup::_exGasTempFactName = "exGasTemp"; +const char* VehicleEFIFactGroup::_throttleOutFactName = "throttleOut"; +const char* VehicleEFIFactGroup::_ptCompFactName = "ptComp"; + + +VehicleEFIFactGroup::VehicleEFIFactGroup(QObject* parent) + : FactGroup(1000, ":/json/Vehicle/EFIFact.json", parent) + , _healthFact (0, _healthFactName, FactMetaData::valueTypeInt8) + , _ecuIndexFact (0, _ecuIndexFactName, FactMetaData::valueTypeFloat) + , _rpmFact (0, _rpmFactName, FactMetaData::valueTypeFloat) + , _fuelConsumedFact (0, _fuelConsumedFactName, FactMetaData::valueTypeFloat) + , _fuelFlowFact (0, _fuelFlowFactName, FactMetaData::valueTypeFloat) + , _engineLoadFact (0, _engineLoadFactName, FactMetaData::valueTypeFloat) + , _throttlePosFact (0, _throttlePosFactName, FactMetaData::valueTypeFloat) + , _sparkTimeFact (0, _sparkTimeFactName, FactMetaData::valueTypeFloat) + , _baroPressFact (0, _baroPressFactName, FactMetaData::valueTypeFloat) + , _intakePressFact (0, _intakePressFactName, FactMetaData::valueTypeFloat) + , _intakeTempFact (0, _intakeTempFactName, FactMetaData::valueTypeFloat) + , _cylinderTempFact (0, _cylinderTempFactName, FactMetaData::valueTypeFloat) + , _ignTimeFact (0, _ignTimeFactName, FactMetaData::valueTypeFloat) + , _injTimeFact (0, _injTimeFactName, FactMetaData::valueTypeFloat) + , _exGasTempFact (0, _exGasTempFactName, FactMetaData::valueTypeFloat) + , _throttleOutFact (0, _throttleOutFactName, FactMetaData::valueTypeFloat) + , _ptCompFact (0, _ptCompFactName, FactMetaData::valueTypeFloat) +{ + _addFact(&_healthFact, _healthFactName); + _addFact(&_ecuIndexFact, _ecuIndexFactName); + _addFact(&_rpmFact, _rpmFactName); + _addFact(&_fuelConsumedFact, _fuelConsumedFactName); + _addFact(&_fuelFlowFact, _fuelFlowFactName); + _addFact(&_engineLoadFact, _engineLoadFactName); + _addFact(&_sparkTimeFact, _sparkTimeFactName); + _addFact(&_throttlePosFact, _throttlePosFactName); + _addFact(&_baroPressFact, _baroPressFactName); + _addFact(&_intakePressFact, _intakePressFactName); + _addFact(&_intakeTempFact, _intakeTempFactName); + _addFact(&_cylinderTempFact, _cylinderTempFactName); + _addFact(&_ignTimeFact, _ignTimeFactName); + _addFact(&_exGasTempFact, _exGasTempFactName); + _addFact(&_injTimeFact, _injTimeFactName); + _addFact(&_throttleOutFact, _throttleOutFactName); + _addFact(&_ptCompFact, _ptCompFactName); + + // Start out as not available "--.--" + _healthFact.setRawValue(qQNaN()); + _ecuIndexFact.setRawValue(qQNaN()); + _rpmFact.setRawValue(qQNaN()); + _fuelConsumedFact.setRawValue(qQNaN()); + _fuelFlowFact.setRawValue(qQNaN()); + _engineLoadFact.setRawValue(qQNaN()); + _sparkTimeFact.setRawValue(qQNaN()); + _throttlePosFact.setRawValue(qQNaN()); + _baroPressFact.setRawValue(qQNaN()); + _intakePressFact.setRawValue(qQNaN()); + _intakeTempFact.setRawValue(qQNaN()); + _cylinderTempFact.setRawValue(qQNaN()); + _ignTimeFact.setRawValue(qQNaN()); + _exGasTempFact.setRawValue(qQNaN()); + _injTimeFact.setRawValue(qQNaN()); + _throttleOutFact.setRawValue(qQNaN()); + _ptCompFact.setRawValue(qQNaN()); +} + +void VehicleEFIFactGroup::handleMessage(Vehicle* /* vehicle */, mavlink_message_t& message) +{ + switch (message.msgid) { + case MAVLINK_MSG_ID_EFI_STATUS: + _handleEFIStatus(message); + break; + default: + break; + } +} + +void VehicleEFIFactGroup::_handleEFIStatus(mavlink_message_t& message) +{ + mavlink_efi_status_t efi; + mavlink_msg_efi_status_decode(&message, &efi); + + health()->setRawValue (efi.health == INT8_MAX ? qQNaN() : efi.health); + ecuIndex()->setRawValue (efi.ecu_index); + rpm()->setRawValue (efi.rpm); + fuelConsumed()->setRawValue (efi.fuel_consumed); + fuelFlow()->setRawValue (efi.fuel_flow); + engineLoad()->setRawValue (efi.engine_load); + throttlePos()->setRawValue (efi.throttle_position); + sparkTime()->setRawValue (efi.spark_dwell_time); + baroPress()->setRawValue (efi.barometric_pressure); + intakePress()->setRawValue (efi.intake_manifold_pressure); + intakeTemp()->setRawValue (efi.intake_manifold_temperature); + cylinderTemp()->setRawValue (efi.cylinder_head_temperature); + ignTime()->setRawValue (efi.ignition_timing); + injTime()->setRawValue (efi.injection_time); + exGasTemp()->setRawValue (efi.exhaust_gas_temperature); + throttleOut()->setRawValue (efi.throttle_out); + ptComp()->setRawValue (efi.pt_compensation); +} diff --git a/src/Vehicle/VehicleEFIFactGroup.h b/src/Vehicle/VehicleEFIFactGroup.h new file mode 100644 index 00000000000..879a7a91c74 --- /dev/null +++ b/src/Vehicle/VehicleEFIFactGroup.h @@ -0,0 +1,94 @@ +#pragma once + +#include "FactGroup.h" +#include "QGCMAVLink.h" + +class VehicleEFIFactGroup : public FactGroup +{ + Q_OBJECT + +public: + VehicleEFIFactGroup(QObject* parent = nullptr); + + Q_PROPERTY(Fact* health READ health CONSTANT) + Q_PROPERTY(Fact* ecuIndex READ ecuIndex CONSTANT) + Q_PROPERTY(Fact* rpm READ rpm CONSTANT) + Q_PROPERTY(Fact* fuelConsumed READ fuelConsumed CONSTANT) + Q_PROPERTY(Fact* fuelFlow READ fuelFlow CONSTANT) + Q_PROPERTY(Fact* engineLoad READ engineLoad CONSTANT) + Q_PROPERTY(Fact* throttlePos READ throttlePos CONSTANT) + Q_PROPERTY(Fact* sparkTime READ sparkTime CONSTANT) + Q_PROPERTY(Fact* baroPress READ baroPress CONSTANT) + Q_PROPERTY(Fact* intakePress READ intakePress CONSTANT) + Q_PROPERTY(Fact* intakeTemp READ intakeTemp CONSTANT) + Q_PROPERTY(Fact* cylinderTemp READ cylinderTemp CONSTANT) + Q_PROPERTY(Fact* ignTime READ ignTime CONSTANT) + Q_PROPERTY(Fact* injTime READ injTime CONSTANT) + Q_PROPERTY(Fact* exGasTemp READ exGasTemp CONSTANT) + Q_PROPERTY(Fact* throttleOut READ throttleOut CONSTANT) + Q_PROPERTY(Fact* ptComp READ ptComp CONSTANT) + Q_PROPERTY(Fact* ignVoltage READ ignVoltage CONSTANT) + + Fact* health () { return &_healthFact; } + Fact* ecuIndex () { return &_ecuIndexFact; } + Fact* rpm () { return &_rpmFact; } + Fact* fuelConsumed () { return &_fuelConsumedFact; } + Fact* fuelFlow () { return &_fuelFlowFact; } + Fact* engineLoad () { return &_engineLoadFact; } + Fact* throttlePos () { return &_throttlePosFact; } + Fact* sparkTime () { return &_sparkTimeFact; } + Fact* baroPress () { return &_baroPressFact; } + Fact* intakePress () { return &_intakePressFact; } + Fact* intakeTemp () { return &_intakeTempFact; } + Fact* cylinderTemp () { return &_cylinderTempFact; } + Fact* ignTime () { return &_ignTimeFact; } + Fact* injTime () { return &_injTimeFact; } + Fact* exGasTemp () { return &_exGasTempFact; } + Fact* throttleOut () { return &_throttleOutFact; } + Fact* ptComp () { return &_ptCompFact; } + Fact* ignVoltage () { return &_ignVoltageFact; } + + // Overrides from FactGroup + virtual void handleMessage(Vehicle* vehicle, mavlink_message_t& message) override; + + static const char* _healthFactName; + static const char* _ecuIndexFactName; + static const char* _rpmFactName; + static const char* _fuelConsumedFactName; + static const char* _fuelFlowFactName; + static const char* _engineLoadFactName; + static const char* _throttlePosFactName; + static const char* _sparkTimeFactName; + static const char* _baroPressFactName; + static const char* _intakePressFactName; + static const char* _intakeTempFactName; + static const char* _cylinderTempFactName; + static const char* _ignTimeFactName; + static const char* _injTimeFactName; + static const char* _exGasTempFactName; + static const char* _throttleOutFactName; + static const char* _ptCompFactName; + static const char* _ignVoltageFactName; + +protected: + void _handleEFIStatus(mavlink_message_t& message); + + Fact _healthFact; + Fact _ecuIndexFact; + Fact _rpmFact; + Fact _fuelConsumedFact; + Fact _fuelFlowFact; + Fact _engineLoadFact; + Fact _throttlePosFact; + Fact _sparkTimeFact; + Fact _baroPressFact; + Fact _intakePressFact; + Fact _intakeTempFact; + Fact _cylinderTempFact; + Fact _ignTimeFact; + Fact _injTimeFact; + Fact _exGasTempFact; + Fact _throttleOutFact; + Fact _ptCompFact; + Fact _ignVoltageFact; +}; diff --git a/src/Vehicle/VehicleGeneratorFactGroup.cc b/src/Vehicle/VehicleGeneratorFactGroup.cc new file mode 100644 index 00000000000..9cfbd7d936f --- /dev/null +++ b/src/Vehicle/VehicleGeneratorFactGroup.cc @@ -0,0 +1,110 @@ +#include "VehicleGeneratorFactGroup.h" +#include "Vehicle.h" +#include + +const char* VehicleGeneratorFactGroup::_statusFactName = "status"; +const char* VehicleGeneratorFactGroup::_genSpeedFactName = "genSpeed"; +const char* VehicleGeneratorFactGroup::_batteryCurrentFactName = "batteryCurrent"; +const char* VehicleGeneratorFactGroup::_loadCurrentFactName = "loadCurrent"; +const char* VehicleGeneratorFactGroup::_powerGeneratedFactName = "powerGenerated"; +const char* VehicleGeneratorFactGroup::_busVoltageFactName = "busVoltage"; +const char* VehicleGeneratorFactGroup::_rectifierTempFactName = "rectifierTemp"; +const char* VehicleGeneratorFactGroup::_batCurrentSetpointFactName = "batCurrentSetpoint"; +const char* VehicleGeneratorFactGroup::_genTempFactName = "genTemp"; +const char* VehicleGeneratorFactGroup::_runtimeFactName = "runtime"; +const char* VehicleGeneratorFactGroup::_timeMaintenanceFactName = "timeMaintenance"; + +VehicleGeneratorFactGroup::VehicleGeneratorFactGroup(QObject* parent) + : FactGroup(1000, ":/json/Vehicle/GeneratorFact.json", parent) + , _statusFact (0, _statusFactName, FactMetaData::valueTypeUint64) + , _genSpeedFact (0, _genSpeedFactName, FactMetaData::valueTypeUint16) + , _batteryCurrentFact (0, _batteryCurrentFactName, FactMetaData::valueTypeFloat) + , _loadCurrentFact (0, _loadCurrentFactName, FactMetaData::valueTypeFloat) + , _powerGeneratedFact (0, _powerGeneratedFactName, FactMetaData::valueTypeFloat) + , _busVoltageFact (0, _busVoltageFactName, FactMetaData::valueTypeFloat) + , _rectifierTempFact (0, _rectifierTempFactName, FactMetaData::valueTypeInt16) + , _batCurrentSetpointFact (0, _batCurrentSetpointFactName, FactMetaData::valueTypeFloat) + , _genTempFact (0, _genTempFactName, FactMetaData::valueTypeInt16) + , _runtimeFact (0, _runtimeFactName, FactMetaData::valueTypeUint32) + , _timeMaintenanceFact (0, _timeMaintenanceFactName, FactMetaData::valueTypeInt32) +{ + _addFact(&_statusFact, _statusFactName); + _addFact(&_genSpeedFact, _genSpeedFactName); + _addFact(&_batteryCurrentFact, _batteryCurrentFactName); + _addFact(&_loadCurrentFact, _loadCurrentFactName); + _addFact(&_powerGeneratedFact, _powerGeneratedFactName); + _addFact(&_busVoltageFact, _busVoltageFactName); + _addFact(&_batCurrentSetpointFact, _batCurrentSetpointFactName); + _addFact(&_rectifierTempFact, _rectifierTempFactName); + _addFact(&_genTempFact, _genTempFactName); + _addFact(&_runtimeFact, _runtimeFactName); + _addFact(&_timeMaintenanceFact, _timeMaintenanceFactName); + + // Start out as not available "--.--" + _statusFact.setRawValue(qQNaN()); + _genSpeedFact.setRawValue(qQNaN()); + _batteryCurrentFact.setRawValue(qQNaN()); + _loadCurrentFact.setRawValue(qQNaN()); + _powerGeneratedFact.setRawValue(qQNaN()); + _busVoltageFact.setRawValue(qQNaN()); + _batCurrentSetpointFact.setRawValue(qQNaN()); + _rectifierTempFact.setRawValue(qQNaN()); + _genTempFact.setRawValue(qQNaN()); + _runtimeFact.setRawValue(qQNaN()); + _timeMaintenanceFact.setRawValue(qQNaN()); +} + +void VehicleGeneratorFactGroup::handleMessage(Vehicle* /* vehicle */, mavlink_message_t& message) +{ + switch (message.msgid) { + case MAVLINK_MSG_ID_GENERATOR_STATUS: + _handleGeneratorStatus(message); + break; + default: + break; + } +} + +void VehicleGeneratorFactGroup::_handleGeneratorStatus(mavlink_message_t& message) +{ + mavlink_generator_status_t generator; + mavlink_msg_generator_status_decode(&message, &generator); + + status()->setRawValue (generator.status == UINT16_MAX ? qQNaN() : generator.status); + _updateGeneratorFlags(); + genSpeed()->setRawValue (generator.generator_speed == UINT16_MAX ? qQNaN() : generator.generator_speed); + batteryCurrent()->setRawValue (generator.battery_current); + loadCurrent()->setRawValue (generator.load_current); + powerGenerated()->setRawValue (generator.power_generated); + busVoltage()->setRawValue (generator.bus_voltage); + rectifierTemp()->setRawValue (generator.rectifier_temperature == INT16_MAX ? qQNaN() : generator.rectifier_temperature); + batCurrentSetpoint()->setRawValue (generator.bat_current_setpoint); + genTemp()->setRawValue (generator.generator_temperature == INT16_MAX ? qQNaN() : generator.generator_temperature); + runtime()->setRawValue (generator.runtime == UINT32_MAX ? qQNaN() : generator.runtime); + timeMaintenance()->setRawValue (generator.time_until_maintenance == INT32_MAX ? qQNaN() : generator.time_until_maintenance); +} + +void VehicleGeneratorFactGroup::_updateGeneratorFlags() { + + // Check the status received, and convert it to a List with the state of each flag + int statusFlag = _statusFact.rawValue().toInt(); + + // No need to update the list if we have the same flags + if ( statusFlag == _prevFlag) { + return; + } + + _prevFlag = statusFlag; + _flagsListGenerator.clear(); + + std::bitset<23> bitsetFlags(statusFlag); + + for (size_t i=0; i Date: Thu, 24 Aug 2023 00:41:30 +0200 Subject: [PATCH 115/118] Vehicle.h: remove unused variable --- src/Vehicle/Vehicle.h | 1 - 1 file changed, 1 deletion(-) diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index db2887dcf7a..da2461305b9 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -1493,7 +1493,6 @@ private slots: static const char* _joystickEnabledSettingsKey; // Terrain query members, used to get terrain altitude for doSetHome() - QTimer _updateDoSetHomeTerrainTimer; TerrainAtCoordinateQuery* _currentDoSetHomeTerrainAtCoordinateQuery = nullptr; QGeoCoordinate _doSetHomeCoordinate; }; From 9e652a812b21740080b36086c58b49bf92a581fa Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 25 Aug 2023 00:18:07 +0200 Subject: [PATCH 116/118] Vehicle: move _doSetHomeTerrainReceived to private slots --- src/Vehicle/Vehicle.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index da2461305b9..2ecf356e0a1 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -1056,6 +1056,7 @@ private slots: void _orbitTelemetryTimeout (); void _updateFlightTime (); void _gotProgressUpdate (float progressValue); + void _doSetHomeTerrainReceived (bool success, QList heights); private: void _loadJoystickSettings (); @@ -1120,9 +1121,6 @@ private slots: static void _rebootCommandResultHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode); - // This is called after we get terrain data triggered from a doSetHome() - void _doSetHomeTerrainReceived (bool success, QList heights); - int _id; ///< Mavlink system id int _defaultComponentId; bool _offlineEditingVehicle = false; ///< true: This Vehicle is a "disconnected" vehicle for ui use while offline editing From 22b3408f0382d2555bf016023ad757a37ed8b2fb Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 25 Aug 2023 00:16:40 +0200 Subject: [PATCH 117/118] Vehicle: add altitude above terrain fact and implementation --- src/Vehicle/Vehicle.cc | 67 ++++++++++++++++++++++++++++++++++++ src/Vehicle/Vehicle.h | 13 +++++++ src/Vehicle/VehicleFact.json | 7 ++++ 3 files changed, 87 insertions(+) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 3b2874fbbe0..a8083393600 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -84,6 +84,7 @@ const char* Vehicle::_groundSpeedFactName = "groundSpeed"; const char* Vehicle::_climbRateFactName = "climbRate"; const char* Vehicle::_altitudeRelativeFactName = "altitudeRelative"; const char* Vehicle::_altitudeAMSLFactName = "altitudeAMSL"; +const char* Vehicle::_altitudeAboveTerrFactName = "altitudeAboveTerr"; const char* Vehicle::_altitudeTuningFactName = "altitudeTuning"; const char* Vehicle::_altitudeTuningSetpointFactName = "altitudeTuningSetpoint"; const char* Vehicle::_flightDistanceFactName = "flightDistance"; @@ -148,6 +149,7 @@ Vehicle::Vehicle(LinkInterface* link, , _climbRateFact (0, _climbRateFactName, FactMetaData::valueTypeDouble) , _altitudeRelativeFact (0, _altitudeRelativeFactName, FactMetaData::valueTypeDouble) , _altitudeAMSLFact (0, _altitudeAMSLFactName, FactMetaData::valueTypeDouble) + , _altitudeAboveTerrFact (0, _altitudeAboveTerrFactName, FactMetaData::valueTypeDouble) , _altitudeTuningFact (0, _altitudeTuningFactName, FactMetaData::valueTypeDouble) , _altitudeTuningSetpointFact (0, _altitudeTuningSetpointFactName, FactMetaData::valueTypeDouble) , _xTrackErrorFact (0, _xTrackErrorFactName, FactMetaData::valueTypeDouble) @@ -260,6 +262,9 @@ Vehicle::Vehicle(LinkInterface* link, // Start csv logger connect(&_csvLogTimer, &QTimer::timeout, this, &Vehicle::_writeCsvLine); _csvLogTimer.start(1000); + + // Start timer to limit altitude above terrain queries + _altitudeAboveTerrQueryTimer.restart(); } // Disconnected Vehicle for offline editing @@ -296,6 +301,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, , _climbRateFact (0, _climbRateFactName, FactMetaData::valueTypeDouble) , _altitudeRelativeFact (0, _altitudeRelativeFactName, FactMetaData::valueTypeDouble) , _altitudeAMSLFact (0, _altitudeAMSLFactName, FactMetaData::valueTypeDouble) + , _altitudeAboveTerrFact (0, _altitudeAboveTerrFactName, FactMetaData::valueTypeDouble) , _altitudeTuningFact (0, _altitudeTuningFactName, FactMetaData::valueTypeDouble) , _altitudeTuningSetpointFact (0, _altitudeTuningSetpointFactName, FactMetaData::valueTypeDouble) , _xTrackErrorFact (0, _xTrackErrorFactName, FactMetaData::valueTypeDouble) @@ -361,6 +367,9 @@ void Vehicle::_commonInit() connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateDistanceToGCS); connect(this, &Vehicle::homePositionChanged, this, &Vehicle::_updateDistanceHeadingToHome); connect(this, &Vehicle::hobbsMeterChanged, this, &Vehicle::_updateHobbsMeter); + connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateAltAboveTerrain); + // Initialize alt above terrain to Nan so frontend can display it correctly in case the terrain query had no response + _altitudeAboveTerrFact.setRawValue(qQNaN()); connect(_toolbox->qgcPositionManager(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateDistanceToGCS); connect(_toolbox->qgcPositionManager(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateHomepoint); @@ -428,6 +437,7 @@ void Vehicle::_commonInit() _addFact(&_climbRateFact, _climbRateFactName); _addFact(&_altitudeRelativeFact, _altitudeRelativeFactName); _addFact(&_altitudeAMSLFact, _altitudeAMSLFactName); + _addFact(&_altitudeAboveTerrFact, _altitudeAboveTerrFactName); _addFact(&_altitudeTuningFact, _altitudeTuningFactName); _addFact(&_altitudeTuningSetpointFact, _altitudeTuningSetpointFactName); _addFact(&_xTrackErrorFact, _xTrackErrorFactName); @@ -4193,6 +4203,63 @@ void Vehicle::_doSetHomeTerrainReceived(bool success, QList heights) _doSetHomeCoordinate = QGeoCoordinate(); // So isValid() will no longer return true, for extra safety } +void Vehicle::_updateAltAboveTerrain() +{ + // We won't do another query if the previous query was done closer than 2 meters from current position + // or if altitude change has been less than 0.5 meters since then. + const qreal minimumDistanceTraveled = 2; + const float minimumAltitudeChanged = 0.5f; + + // This is not super elegant but it works to limit the amount of queries we do. It seems more than 500ms is not possible to get + // serviced on time. It is not a big deal if it is not serviced on time as terrain queries can manage that just fine, but QGC would + // use resources to service those queries, and it is pointless, so this is a quick workaround to not waste that little computing time + int altitudeAboveTerrQueryMinInterval = 500; + if (_altitudeAboveTerrQueryTimer.elapsed() < altitudeAboveTerrQueryMinInterval) { + // qCDebug(VehicleLog) << "_updateAltAboveTerrain: minimum 500ms interval between queries not reached, returning"; + return; + } + // Sanity check, although it is very unlikely that vehicle coordinate is not valid + if (_coordinate.isValid()) { + // Check for minimum distance and altitude traveled before doing query, to not do a lot of queries of the same data + if (_altitudeAboveTerrLastCoord.isValid() && !qIsNaN(_altitudeAboveTerrLastRelAlt)) { + if (_altitudeAboveTerrLastCoord.distanceTo(_coordinate) < minimumDistanceTraveled && fabs(_altitudeRelativeFact.rawValue().toFloat() - _altitudeAboveTerrLastRelAlt) < minimumAltitudeChanged ) { + return; + } + } + _altitudeAboveTerrLastCoord = _coordinate; + _altitudeAboveTerrLastRelAlt = _altitudeRelativeFact.rawValue().toFloat(); + + // If for some reason we already did a query and it hasn't arrived yet, disconnect signals and unset current query. TerrainQuery system will + // automatically delete that forgotten query. + if (_altitudeAboveTerrTerrainAtCoordinateQuery) { + // qCDebug(VehicleLog) << "_updateAltAboveTerrain: cleaning previous query, no longer needed"; + disconnect(_altitudeAboveTerrTerrainAtCoordinateQuery, &TerrainAtCoordinateQuery::terrainDataReceived, this, &Vehicle::_altitudeAboveTerrainReceived); + _altitudeAboveTerrTerrainAtCoordinateQuery = nullptr; + } + // Now setup and trigger the new terrain query + _altitudeAboveTerrTerrainAtCoordinateQuery = new TerrainAtCoordinateQuery(true /* autoDelet */); + connect(_altitudeAboveTerrTerrainAtCoordinateQuery, &TerrainAtCoordinateQuery::terrainDataReceived, this, &Vehicle::_altitudeAboveTerrainReceived); + QList rgCoord; + rgCoord.append(_coordinate); + _altitudeAboveTerrTerrainAtCoordinateQuery->requestData(rgCoord); + _altitudeAboveTerrQueryTimer.restart(); + } +} + +void Vehicle::_altitudeAboveTerrainReceived(bool success, QList heights) +{ + if (!success) { + qCDebug(VehicleLog) << "_altitudeAboveTerrainReceived: terrain data not available for vehicle coordinate"; + } else { + // Query was succesful, save the data. + double terrainAltitude = heights[0]; + double altitudeAboveTerrain = altitudeAMSL()->rawValue().toDouble() - terrainAltitude; + _altitudeAboveTerrFact.setRawValue(altitudeAboveTerrain); + } + // Clean up + _altitudeAboveTerrTerrainAtCoordinateQuery = nullptr; +} + void Vehicle::gimbalControlValue(double pitch, double yaw) { if (apmFirmware()) { diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 2ecf356e0a1..87bf0b2781d 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -295,6 +295,7 @@ class Vehicle : public FactGroup Q_PROPERTY(Fact* climbRate READ climbRate CONSTANT) Q_PROPERTY(Fact* altitudeRelative READ altitudeRelative CONSTANT) Q_PROPERTY(Fact* altitudeAMSL READ altitudeAMSL CONSTANT) + Q_PROPERTY(Fact* altitudeAboveTerr READ altitudeAboveTerr CONSTANT) Q_PROPERTY(Fact* altitudeTuning READ altitudeTuning CONSTANT) Q_PROPERTY(Fact* altitudeTuningSetpoint READ altitudeTuningSetpoint CONSTANT) Q_PROPERTY(Fact* xTrackError READ xTrackError CONSTANT) @@ -688,6 +689,7 @@ class Vehicle : public FactGroup Fact* climbRate () { return &_climbRateFact; } Fact* altitudeRelative () { return &_altitudeRelativeFact; } Fact* altitudeAMSL () { return &_altitudeAMSLFact; } + Fact* altitudeAboveTerr () { return &_altitudeAboveTerrFact; } Fact* altitudeTuning () { return &_altitudeTuningFact; } Fact* altitudeTuningSetpoint () { return &_altitudeTuningSetpointFact; } Fact* xTrackError () { return &_xTrackErrorFact; } @@ -1057,6 +1059,8 @@ private slots: void _updateFlightTime (); void _gotProgressUpdate (float progressValue); void _doSetHomeTerrainReceived (bool success, QList heights); + void _updateAltAboveTerrain (); + void _altitudeAboveTerrainReceived (bool sucess, QList heights); private: void _loadJoystickSettings (); @@ -1392,6 +1396,7 @@ private slots: Fact _climbRateFact; Fact _altitudeRelativeFact; Fact _altitudeAMSLFact; + Fact _altitudeAboveTerrFact; Fact _altitudeTuningFact; Fact _altitudeTuningSetpointFact; Fact _xTrackErrorFact; @@ -1451,6 +1456,7 @@ private slots: static const char* _climbRateFactName; static const char* _altitudeRelativeFactName; static const char* _altitudeAMSLFactName; + static const char* _altitudeAboveTerrFactName; static const char* _altitudeTuningFactName; static const char* _altitudeTuningSetpointFactName; static const char* _xTrackErrorFactName; @@ -1493,6 +1499,13 @@ private slots: // Terrain query members, used to get terrain altitude for doSetHome() TerrainAtCoordinateQuery* _currentDoSetHomeTerrainAtCoordinateQuery = nullptr; QGeoCoordinate _doSetHomeCoordinate; + + // Terrain query members, used to get altitude above terrain Fact + QElapsedTimer _altitudeAboveTerrQueryTimer; + TerrainAtCoordinateQuery* _altitudeAboveTerrTerrainAtCoordinateQuery = nullptr; + // We use this to limit above terrain altitude queries based on distance and altitude change + QGeoCoordinate _altitudeAboveTerrLastCoord; + float _altitudeAboveTerrLastRelAlt = qQNaN(); }; Q_DECLARE_METATYPE(Vehicle::MavCmdResultFailureCode_t) diff --git a/src/Vehicle/VehicleFact.json b/src/Vehicle/VehicleFact.json index 3e7be998cee..5336b00c5a4 100644 --- a/src/Vehicle/VehicleFact.json +++ b/src/Vehicle/VehicleFact.json @@ -80,6 +80,13 @@ "decimalPlaces": 1, "units": "m" }, +{ + "name": "altitudeAboveTerr", + "shortDesc": "Alt (Above Terrain)", + "type": "double", + "decimalPlaces": 1, + "units": "m" +}, { "name": "flightDistance", "shortDesc": "Flight Distance", From 442222ba31123ac5f7cb13b1be89067543befb71 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Mon, 20 Nov 2023 15:03:47 +0000 Subject: [PATCH 118/118] Update PX4 Firmware metadata Mon Nov 20 15:03:47 UTC 2023 --- src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml | 8 -------- 1 file changed, 8 deletions(-) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 9424f89e61f..817aedcc9d9 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -3893,14 +3893,6 @@ m 2 - - Maximum altitude for multicopters - The system will obey this limit as a hard altitude limit. This setting will be consolidated with the GF_MAX_VER_DIST parameter. A negative value indicates no altitude limitation. - -1 - 10000 - m - 2 - Multicopter max rotation Maximum allowed angular velocity around each axis allowed in the landed state.