diff --git a/qgcresources.qrc b/qgcresources.qrc index 049b2a4fdd3f4c70150fde0c5f32c130f25e1fb0..95e62681cb85895a6bf358f9341f402c6dab44f6 100644 --- a/qgcresources.qrc +++ b/qgcresources.qrc @@ -273,6 +273,8 @@ src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml + src/FirmwarePlugin/APM/Copter3.4.OfflineEditing.params + src/FirmwarePlugin/APM/Plane3.7.OfflineEditing.params src/FirmwarePlugin/GeoFenceEditor.qml diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index 0b11ea73d1d84bff54f3bd425a942c941a4863c2..51b6481b9a55ff9bd226b6a9cea7367313793fbc 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -39,7 +39,7 @@ const char* ParameterLoader::_cachedMetaDataFilePrefix = "ParameterFactMetaData" ParameterLoader::ParameterLoader(Vehicle* vehicle) : QObject(vehicle) , _vehicle(vehicle) - , _mavlink(qgcApp()->toolbox()->mavlinkProtocol()) + , _mavlink(NULL) , _parametersReady(false) , _initialLoadComplete(false) , _waitingForDefaultComponent(false) @@ -53,8 +53,12 @@ ParameterLoader::ParameterLoader(Vehicle* vehicle) , _initialRequestRetryCount(0) , _totalParamCount(0) { - Q_ASSERT(_vehicle); - Q_ASSERT(_mavlink); + if (_vehicle->isOfflineEditingVehicle()) { + _loadOfflineEditingParams(); + return; + } + + _mavlink = qgcApp()->toolbox()->mavlinkProtocol(); // We signal this to ouselves in order to start timer on our thread connect(this, &ParameterLoader::restartWaitingParamTimer, this, &ParameterLoader::_restartWaitingParamTimer); @@ -1212,3 +1216,71 @@ QString ParameterLoader::_remapParamNameToVersion(const QString& paramName) return mappedParamName; } + +/// The offline editing vehicle can have custom loaded params bolted into it. +void ParameterLoader::_loadOfflineEditingParams(void) +{ + QString paramFilename = _vehicle->firmwarePlugin()->offlineEditingParamFile(_vehicle); + if (paramFilename.isEmpty()) { + return; + } + + QFile paramFile(paramFilename); + if (!paramFile.open(QFile::ReadOnly)) { + qCWarning(ParameterLoaderLog) << "Unable to open offline editing params file" << paramFilename; + } + + QTextStream paramStream(¶mFile); + + while (!paramStream.atEnd()) { + QString line = paramStream.readLine(); + + if (line.startsWith("#")) { + continue; + } + + QStringList paramData = line.split("\t"); + Q_ASSERT(paramData.count() == 5); + + _defaultComponentId = paramData.at(1).toInt(); + QString paramName = paramData.at(2); + QString valStr = paramData.at(3); + MAV_PARAM_TYPE paramType = static_cast(paramData.at(4).toUInt()); + + QVariant paramValue; + switch (paramType) { + case MAV_PARAM_TYPE_REAL32: + paramValue = QVariant(valStr.toFloat()); + break; + case MAV_PARAM_TYPE_UINT32: + paramValue = QVariant(valStr.toUInt()); + break; + case MAV_PARAM_TYPE_INT32: + paramValue = QVariant(valStr.toInt()); + break; + case MAV_PARAM_TYPE_UINT16: + paramValue = QVariant((quint16)valStr.toUInt()); + break; + case MAV_PARAM_TYPE_INT16: + paramValue = QVariant((qint16)valStr.toInt()); + break; + case MAV_PARAM_TYPE_UINT8: + paramValue = QVariant((quint8)valStr.toUInt()); + break; + case MAV_PARAM_TYPE_INT8: + paramValue = QVariant((qint8)valStr.toUInt()); + break; + default: + qCritical() << "Unknown type" << paramType; + paramValue = QVariant(valStr.toInt()); + break; + } + + Fact* fact = new Fact(_defaultComponentId, paramName, _mavTypeToFactType(paramType), this); + _mapParameterName2Variant[_defaultComponentId][paramName] = QVariant::fromValue(fact); + } + + _addMetaDataToDefaultComponent(); + _parametersReady = true; + _initialLoadComplete = true; +} diff --git a/src/FactSystem/ParameterLoader.h b/src/FactSystem/ParameterLoader.h index 515181e623ea6a17034f708def3dd2dd42ea50d9..5c2972e83d81ff4027628bf3a653c0dcfb860c0b 100644 --- a/src/FactSystem/ParameterLoader.h +++ b/src/FactSystem/ParameterLoader.h @@ -125,6 +125,7 @@ private: void _tryCacheHashLoad(int uasId, int componentId, QVariant hash_value); void _addMetaDataToDefaultComponent(void); QString _remapParamNameToVersion(const QString& paramName); + void _loadOfflineEditingParams(void); MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType); FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType); diff --git a/src/FirmwarePlugin/APM/APMGeoFenceManager.cc b/src/FirmwarePlugin/APM/APMGeoFenceManager.cc index 140a45b281d92abcbc434e6043816abe3a688477..dec2c8f06fa82f0e149ea9fac03927fb274ed6e5 100644 --- a/src/FirmwarePlugin/APM/APMGeoFenceManager.cc +++ b/src/FirmwarePlugin/APM/APMGeoFenceManager.cc @@ -31,6 +31,10 @@ APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle) { connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &APMGeoFenceManager::_mavlinkMessageReceived); connect(_vehicle->getParameterLoader(), &ParameterLoader::parametersReady, this, &APMGeoFenceManager::_parametersReady); + + if (_vehicle->getParameterLoader()->parametersAreReady()) { + _parametersReady(); + } } APMGeoFenceManager::~APMGeoFenceManager() @@ -40,6 +44,10 @@ APMGeoFenceManager::~APMGeoFenceManager() void APMGeoFenceManager::sendToVehicle(void) { + if (_vehicle->isOfflineEditingVehicle()) { + return; + } + if (_readTransactionInProgress) { _sendError(InternalError, QStringLiteral("Geo-Fence write attempted while read in progress.")); return; @@ -82,6 +90,10 @@ void APMGeoFenceManager::sendToVehicle(void) void APMGeoFenceManager::loadFromVehicle(void) { + if (_vehicle->isOfflineEditingVehicle()) { + return; + } + _polygon.clear(); if (!_geoFenceSupported()) { diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h index 06cd34ed4ae181684b21d6a149cb7c6b2699d3ef..3d43481a1494bcf65baf71bed4b42653dc88fa4c 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h @@ -67,6 +67,7 @@ public: bool multiRotorCoaxialMotors(Vehicle* vehicle) final; bool multiRotorXConfig(Vehicle* vehicle) final; QString geoFenceRadiusParam(Vehicle* vehicle) final; + QString offlineEditingParamFile(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Copter.OfflineEditing.params"); } private: static bool _remapParamNameIntialized; diff --git a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h index ebe91084c50247b30d8e1c497bb23dbc01f521d0..111abf4fac86713a3e2c6b283ac7403c7c93dc03 100644 --- a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h @@ -54,6 +54,9 @@ class ArduPlaneFirmwarePlugin : public APMFirmwarePlugin public: ArduPlaneFirmwarePlugin(void); + + // Overrides from FirmwarePlugin + QString offlineEditingParamFile(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Plane.OfflineEditing.params"); } }; #endif diff --git a/src/FirmwarePlugin/APM/Copter3.4.OfflineEditing.params b/src/FirmwarePlugin/APM/Copter3.4.OfflineEditing.params new file mode 100644 index 0000000000000000000000000000000000000000..b65b77adea34afb462885c9743e46b5e62610a81 --- /dev/null +++ b/src/FirmwarePlugin/APM/Copter3.4.OfflineEditing.params @@ -0,0 +1,585 @@ +# Onboard parameters for vehicle 1 +# +# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT) +1 1 ACCEL_Z_D 0.000000000000000000 9 +1 1 ACCEL_Z_FILT 20.000000000000000000 9 +1 1 ACCEL_Z_I 1.000000000000000000 9 +1 1 ACCEL_Z_IMAX 800.000000000000000000 9 +1 1 ACCEL_Z_P 0.500000000000000000 9 +1 1 ACRO_BAL_PITCH 1.000000000000000000 9 +1 1 ACRO_BAL_ROLL 1.000000000000000000 9 +1 1 ACRO_EXPO 0.300000011920928955 9 +1 1 ACRO_RP_P 4.500000000000000000 9 +1 1 ACRO_TRAINER 2 2 +1 1 ACRO_YAW_P 3.000000000000000000 9 +1 1 ADSB_ENABLE 0 2 +1 1 AHRS_COMP_BETA 0.100000001490116119 9 +1 1 AHRS_EKF_TYPE 2 2 +1 1 AHRS_GPS_GAIN 1.000000000000000000 9 +1 1 AHRS_GPS_MINSATS 6 2 +1 1 AHRS_GPS_USE 1 2 +1 1 AHRS_ORIENTATION 0 2 +1 1 AHRS_RP_P 0.200000002980232239 9 +1 1 AHRS_TRIM_X 0.000000000000000000 9 +1 1 AHRS_TRIM_Y 0.000000000000000000 9 +1 1 AHRS_TRIM_Z 0.000000000000000000 9 +1 1 AHRS_WIND_MAX 0 2 +1 1 AHRS_YAW_P 0.200000002980232239 9 +1 1 ANGLE_MAX 3000 4 +1 1 ARMING_CHECK 1 2 +1 1 ATC_ACCEL_P_MAX 110000.000000000000000000 9 +1 1 ATC_ACCEL_R_MAX 110000.000000000000000000 9 +1 1 ATC_ACCEL_Y_MAX 18000.000000000000000000 9 +1 1 ATC_ANGLE_BOOST 1 2 +1 1 ATC_ANG_LIM_TC 1.000000000000000000 9 +1 1 ATC_ANG_PIT_P 4.500000000000000000 9 +1 1 ATC_ANG_RLL_P 4.500000000000000000 9 +1 1 ATC_ANG_YAW_P 4.500000000000000000 9 +1 1 ATC_RATE_FF_ENAB 1 2 +1 1 ATC_RAT_PIT_D 0.003599999938160181 9 +1 1 ATC_RAT_PIT_FILT 20.000000000000000000 9 +1 1 ATC_RAT_PIT_I 0.090000003576278687 9 +1 1 ATC_RAT_PIT_IMAX 0.444000005722045898 9 +1 1 ATC_RAT_PIT_P 0.135000005364418030 9 +1 1 ATC_RAT_RLL_D 0.003599999938160181 9 +1 1 ATC_RAT_RLL_FILT 20.000000000000000000 9 +1 1 ATC_RAT_RLL_I 0.090000003576278687 9 +1 1 ATC_RAT_RLL_IMAX 0.444000005722045898 9 +1 1 ATC_RAT_RLL_P 0.135000005364418030 9 +1 1 ATC_RAT_YAW_D 0.000000000000000000 9 +1 1 ATC_RAT_YAW_FILT 5.000000000000000000 9 +1 1 ATC_RAT_YAW_I 0.017999999225139618 9 +1 1 ATC_RAT_YAW_IMAX 0.222000002861022949 9 +1 1 ATC_RAT_YAW_P 0.180000007152557373 9 +1 1 ATC_SLEW_YAW 1000.000000000000000000 9 +1 1 ATC_THR_MIX_MAX 0.500000000000000000 9 +1 1 ATC_THR_MIX_MIN 0.100000001490116119 9 +1 1 AUTOTUNE_AGGR 0.100000001490116119 9 +1 1 AUTOTUNE_AXES 7 2 +1 1 AUTOTUNE_MIN_D 0.001000000047497451 9 +1 1 AVD_ENABLE 0 2 +1 1 AVOID_ENABLE 1 2 +1 1 BATT2_AMP_OFFSET 0.000000000000000000 9 +1 1 BATT2_AMP_PERVOL 17.000000000000000000 9 +1 1 BATT2_CAPACITY 3300 6 +1 1 BATT2_CURR_PIN 3 2 +1 1 BATT2_MONITOR 0 2 +1 1 BATT2_VOLT_MULT 10.100000381469726562 9 +1 1 BATT2_VOLT_PIN 2 2 +1 1 BATT_AMP_OFFSET 0.000000000000000000 9 +1 1 BATT_AMP_PERVOLT 17.000000000000000000 9 +1 1 BATT_CAPACITY 5100 6 +1 1 BATT_CURR_PIN 3 2 +1 1 BATT_MONITOR 4 2 +1 1 BATT_VOLT_MULT 12.020000457763671875 9 +1 1 BATT_VOLT_PIN 2 2 +1 1 BRD_CAN_ENABLE 0 2 +1 1 BRD_IMU_TARGTEMP 112 2 +1 1 BRD_PWM_COUNT 6 2 +1 1 BRD_SAFETYENABLE 0 2 +1 1 BRD_SAFETY_MASK 0 6 +1 1 BRD_SBUS_OUT 0 2 +1 1 BRD_SER1_RTSCTS 2 2 +1 1 BRD_SER2_RTSCTS 2 2 +1 1 BRD_SERIAL_NUM 0 4 +1 1 BRD_TYPE 4 2 +1 1 BTN_ENABLE 0 2 +1 1 CAM_DURATION 10 2 +1 1 CAM_FEEDBACK_PIN -1 2 +1 1 CAM_FEEDBACK_POL 1 2 +1 1 CAM_MAX_ROLL 0 4 +1 1 CAM_MIN_INTERVAL 0 4 +1 1 CAM_RELAY_ON 1 2 +1 1 CAM_SERVO_OFF 1100 4 +1 1 CAM_SERVO_ON 1300 4 +1 1 CAM_TRIGG_DIST 0.000000000000000000 9 +1 1 CAM_TRIGG_TYPE 0 2 +1 1 CH10_OPT 0 2 +1 1 CH11_OPT 0 2 +1 1 CH12_OPT 0 2 +1 1 CH7_OPT 18 2 +1 1 CH8_OPT 0 2 +1 1 CH9_OPT 0 2 +1 1 CHUTE_ENABLED 0 2 +1 1 CIRCLE_RADIUS 1000.000000000000000000 9 +1 1 CIRCLE_RATE 20.000000000000000000 9 +1 1 CLI_ENABLED 0 2 +1 1 COMPASS_AUTODEC 1 2 +1 1 COMPASS_CAL_FIT 8.000000000000000000 9 +1 1 COMPASS_DEC 0.000000000000000000 9 +1 1 COMPASS_DEV_ID 73225 6 +1 1 COMPASS_DEV_ID2 66826 6 +1 1 COMPASS_DEV_ID3 263178 6 +1 1 COMPASS_DIA2_X 1.070561408996582031 9 +1 1 COMPASS_DIA2_Y 0.934641718864440918 9 +1 1 COMPASS_DIA2_Z 0.959703207015991211 9 +1 1 COMPASS_DIA3_X 1.000000000000000000 9 +1 1 COMPASS_DIA3_Y 1.000000000000000000 9 +1 1 COMPASS_DIA3_Z 1.000000000000000000 9 +1 1 COMPASS_DIA_X 0.950750410556793213 9 +1 1 COMPASS_DIA_Y 0.820533096790313721 9 +1 1 COMPASS_DIA_Z 1.053607583045959473 9 +1 1 COMPASS_EXTERN2 0 2 +1 1 COMPASS_EXTERN3 0 2 +1 1 COMPASS_EXTERNAL 1 2 +1 1 COMPASS_LEARN 0 2 +1 1 COMPASS_MOT2_X 0.000000000000000000 9 +1 1 COMPASS_MOT2_Y 0.000000000000000000 9 +1 1 COMPASS_MOT2_Z 0.000000000000000000 9 +1 1 COMPASS_MOT3_X 0.000000000000000000 9 +1 1 COMPASS_MOT3_Y 0.000000000000000000 9 +1 1 COMPASS_MOT3_Z 0.000000000000000000 9 +1 1 COMPASS_MOTCT 0 2 +1 1 COMPASS_MOT_X 0.000000000000000000 9 +1 1 COMPASS_MOT_Y 0.000000000000000000 9 +1 1 COMPASS_MOT_Z 0.000000000000000000 9 +1 1 COMPASS_ODI2_X -0.006595933344215155 9 +1 1 COMPASS_ODI2_Y 0.021764066070318222 9 +1 1 COMPASS_ODI2_Z -0.046624138951301575 9 +1 1 COMPASS_ODI3_X 0.000000000000000000 9 +1 1 COMPASS_ODI3_Y 0.000000000000000000 9 +1 1 COMPASS_ODI3_Z 0.000000000000000000 9 +1 1 COMPASS_ODI_X -0.012880827300250530 9 +1 1 COMPASS_ODI_Y 0.000514347339048982 9 +1 1 COMPASS_ODI_Z 0.017157316207885742 9 +1 1 COMPASS_OFS2_X 84.050094604492187500 9 +1 1 COMPASS_OFS2_Y 206.557006835937500000 9 +1 1 COMPASS_OFS2_Z -23.648975372314453125 9 +1 1 COMPASS_OFS3_X 0.000000000000000000 9 +1 1 COMPASS_OFS3_Y 0.000000000000000000 9 +1 1 COMPASS_OFS3_Z 0.000000000000000000 9 +1 1 COMPASS_OFS_X -117.674423217773437500 9 +1 1 COMPASS_OFS_Y -16.476613998413085938 9 +1 1 COMPASS_OFS_Z -14.397478103637695312 9 +1 1 COMPASS_ORIENT 0 2 +1 1 COMPASS_ORIENT2 0 2 +1 1 COMPASS_ORIENT3 0 2 +1 1 COMPASS_PRIMARY 0 2 +1 1 COMPASS_USE 1 2 +1 1 COMPASS_USE2 1 2 +1 1 COMPASS_USE3 1 2 +1 1 DISARM_DELAY 10 2 +1 1 EK2_ABIAS_P_NSE 0.004999999888241291 9 +1 1 EK2_ACC_P_NSE 0.600000023841857910 9 +1 1 EK2_ALT_M_NSE 3.000000000000000000 9 +1 1 EK2_ALT_SOURCE 0 2 +1 1 EK2_CHECK_SCALE 100 4 +1 1 EK2_EAS_I_GATE 400 4 +1 1 EK2_EAS_M_NSE 1.399999976158142090 9 +1 1 EK2_ENABLE 1 2 +1 1 EK2_FLOW_DELAY 10 2 +1 1 EK2_FLOW_I_GATE 300 4 +1 1 EK2_FLOW_M_NSE 0.250000000000000000 9 +1 1 EK2_GBIAS_P_NSE 0.000099999997473788 9 +1 1 EK2_GLITCH_RAD 25 2 +1 1 EK2_GPS_CHECK 31 2 +1 1 EK2_GPS_DELAY 220 4 +1 1 EK2_GPS_TYPE 1 2 +1 1 EK2_GSCL_P_NSE 0.000500000023748726 9 +1 1 EK2_GYRO_P_NSE 0.029999999329447746 9 +1 1 EK2_HGT_DELAY 60 4 +1 1 EK2_HGT_I_GATE 500 4 +1 1 EK2_IMU_MASK 3 2 +1 1 EK2_LOG_MASK 1 2 +1 1 EK2_MAGB_P_NSE 0.000099999997473788 9 +1 1 EK2_MAGE_P_NSE 0.001000000047497451 9 +1 1 EK2_MAG_CAL 3 2 +1 1 EK2_MAG_I_GATE 300 4 +1 1 EK2_MAG_M_NSE 0.050000000745058060 9 +1 1 EK2_MAX_FLOW 2.500000000000000000 9 +1 1 EK2_NOAID_M_NSE 10.000000000000000000 9 +1 1 EK2_POSNE_M_NSE 1.000000000000000000 9 +1 1 EK2_POS_I_GATE 500 4 +1 1 EK2_RNG_I_GATE 500 4 +1 1 EK2_RNG_M_NSE 0.500000000000000000 9 +1 1 EK2_RNG_USE_HGT -1 2 +1 1 EK2_TAU_OUTPUT 25 2 +1 1 EK2_VELD_M_NSE 0.699999988079071045 9 +1 1 EK2_VELNE_M_NSE 0.500000000000000000 9 +1 1 EK2_VEL_I_GATE 500 4 +1 1 EK2_WIND_PSCALE 0.500000000000000000 9 +1 1 EK2_WIND_P_NSE 0.100000001490116119 9 +1 1 EK2_YAW_I_GATE 300 4 +1 1 EK2_YAW_M_NSE 0.500000000000000000 9 +1 1 EKF_ENABLE 0 2 +1 1 EPM_ENABLE 0 2 +1 1 ESC_CALIBRATION 0 2 +1 1 FENCE_ACTION 1 2 +1 1 FENCE_ALT_MAX 100.000000000000000000 9 +1 1 FENCE_ENABLE 1 2 +1 1 FENCE_MARGIN 2.000000000000000000 9 +1 1 FENCE_RADIUS 182.880004882812500000 9 +1 1 FENCE_TOTAL 0 2 +1 1 FENCE_TYPE 3 2 +1 1 FLOW_ENABLE 0 2 +1 1 FLOW_FXSCALER 0 4 +1 1 FLOW_FYSCALER 0 4 +1 1 FLOW_ORIENT_YAW 0 4 +1 1 FLTMODE1 2 2 +1 1 FLTMODE2 5 2 +1 1 FLTMODE3 3 2 +1 1 FLTMODE4 6 2 +1 1 FLTMODE5 6 2 +1 1 FLTMODE6 6 2 +1 1 FRAME 2 2 +1 1 FS_BATT_ENABLE 1 2 +1 1 FS_BATT_MAH 0.000000000000000000 9 +1 1 FS_BATT_VOLTAGE 10.500000000000000000 9 +1 1 FS_CRASH_CHECK 1 2 +1 1 FS_EKF_ACTION 1 2 +1 1 FS_EKF_THRESH 0.800000011920928955 9 +1 1 FS_GCS_ENABLE 1 2 +1 1 FS_THR_ENABLE 1 2 +1 1 FS_THR_VALUE 975 4 +1 1 GCS_PID_MASK 0 4 +1 1 GND_ABS_PRESS 100825.437500000000000000 9 +1 1 GND_ALT_OFFSET 0.000000000000000000 9 +1 1 GND_EFFECT_COMP 0 2 +1 1 GND_PRIMARY 0 2 +1 1 GND_TEMP 26.560714721679687500 9 +1 1 GPS_AUTO_CONFIG 1 2 +1 1 GPS_AUTO_SWITCH 1 2 +1 1 GPS_GNSS_MODE 0 2 +1 1 GPS_GNSS_MODE2 0 2 +1 1 GPS_HDOP_GOOD 250 4 +1 1 GPS_INJECT_TO 127 2 +1 1 GPS_MIN_DGPS 100 2 +1 1 GPS_MIN_ELEV -100 2 +1 1 GPS_NAVFILTER 8 2 +1 1 GPS_RAW_DATA 0 2 +1 1 GPS_SAVE_CFG 0 2 +1 1 GPS_SBAS_MODE 2 2 +1 1 GPS_SBP_LOGMASK -256 4 +1 1 GPS_TYPE 1 2 +1 1 GPS_TYPE2 0 2 +1 1 INS_ACC2OFFS_X 0.000000000000000000 9 +1 1 INS_ACC2OFFS_Y 0.000000000000000000 9 +1 1 INS_ACC2OFFS_Z 0.000000000000000000 9 +1 1 INS_ACC2SCAL_X 1.000000000000000000 9 +1 1 INS_ACC2SCAL_Y 1.000000000000000000 9 +1 1 INS_ACC2SCAL_Z 1.000000000000000000 9 +1 1 INS_ACC3OFFS_X 0.000000000000000000 9 +1 1 INS_ACC3OFFS_Y 0.000000000000000000 9 +1 1 INS_ACC3OFFS_Z 0.000000000000000000 9 +1 1 INS_ACC3SCAL_X 0.000000000000000000 9 +1 1 INS_ACC3SCAL_Y 0.000000000000000000 9 +1 1 INS_ACC3SCAL_Z 0.000000000000000000 9 +1 1 INS_ACCEL_FILTER 20 2 +1 1 INS_ACCOFFS_X 0.000000000000000000 9 +1 1 INS_ACCOFFS_Y 0.000000000000000000 9 +1 1 INS_ACCOFFS_Z 0.000000000000000000 9 +1 1 INS_ACCSCAL_X 1.000000000000000000 9 +1 1 INS_ACCSCAL_Y 1.000000000000000000 9 +1 1 INS_ACCSCAL_Z 1.000000000000000000 9 +1 1 INS_ACC_BODYFIX 2 2 +1 1 INS_GYR2OFFS_X -0.034256070852279663 9 +1 1 INS_GYR2OFFS_Y -0.001716651604510844 9 +1 1 INS_GYR2OFFS_Z -0.009961522184312344 9 +1 1 INS_GYR3OFFS_X 0.000000000000000000 9 +1 1 INS_GYR3OFFS_Y 0.000000000000000000 9 +1 1 INS_GYR3OFFS_Z 0.000000000000000000 9 +1 1 INS_GYROFFS_X -0.039947438985109329 9 +1 1 INS_GYROFFS_Y 0.001942739239893854 9 +1 1 INS_GYROFFS_Z -0.002419092459604144 9 +1 1 INS_GYRO_FILTER 20 2 +1 1 INS_GYR_CAL 1 2 +1 1 INS_PRODUCT_ID 6 4 +1 1 INS_STILL_THRESH 2.500000000000000000 9 +1 1 INS_TRIM_OPTION 1 2 +1 1 INS_USE 1 2 +1 1 INS_USE2 1 2 +1 1 INS_USE3 0 2 +1 1 LAND_REPOSITION 1 2 +1 1 LAND_SPEED 50 4 +1 1 LAND_SPEED_HIGH 0 4 +1 1 LGR_SERVO_DEPLOY 1750 4 +1 1 LGR_SERVO_RTRACT 1250 4 +1 1 LOG_BACKEND_TYPE 1 2 +1 1 LOG_BITMASK 176126 6 +1 1 LOG_DISARMED 0 2 +1 1 LOG_FILE_BUFSIZE 16 2 +1 1 LOG_REPLAY 0 2 +1 1 MAG_ENABLE 1 2 +1 1 MIS_RESTART 0 2 +1 1 MIS_TOTAL 0 4 +1 1 MNT_ANGMAX_PAN 4500 4 +1 1 MNT_ANGMAX_ROL 4500 4 +1 1 MNT_ANGMAX_TIL 0 4 +1 1 MNT_ANGMIN_PAN -4500 4 +1 1 MNT_ANGMIN_ROL -4500 4 +1 1 MNT_ANGMIN_TIL -4500 4 +1 1 MNT_DEFLT_MODE 3 2 +1 1 MNT_JSTICK_SPD 0 2 +1 1 MNT_LEAD_PTCH 0.000000000000000000 9 +1 1 MNT_LEAD_RLL 0.000000000000000000 9 +1 1 MNT_NEUTRAL_X 0.000000000000000000 9 +1 1 MNT_NEUTRAL_Y 0.000000000000000000 9 +1 1 MNT_NEUTRAL_Z 0.000000000000000000 9 +1 1 MNT_RC_IN_PAN 0 2 +1 1 MNT_RC_IN_ROLL 0 2 +1 1 MNT_RC_IN_TILT 0 2 +1 1 MNT_RETRACT_X 0.000000000000000000 9 +1 1 MNT_RETRACT_Y 0.000000000000000000 9 +1 1 MNT_RETRACT_Z 0.000000000000000000 9 +1 1 MNT_STAB_PAN 0 2 +1 1 MNT_STAB_ROLL 0 2 +1 1 MNT_STAB_TILT 0 2 +1 1 MNT_TYPE 0 2 +1 1 MOT_BAT_CURR_MAX 0.000000000000000000 9 +1 1 MOT_BAT_CURR_TC 5.000000000000000000 9 +1 1 MOT_BAT_VOLT_MAX 0.000000000000000000 9 +1 1 MOT_BAT_VOLT_MIN 0.000000000000000000 9 +1 1 MOT_HOVER_LEARN 2 2 +1 1 MOT_PWM_MAX 0 4 +1 1 MOT_PWM_MIN 0 4 +1 1 MOT_PWM_TYPE 0 2 +1 1 MOT_SPIN_ARM 0.100000001490116119 9 +1 1 MOT_SPIN_MAX 0.949999988079071045 9 +1 1 MOT_SPIN_MIN 0.150000005960464478 9 +1 1 MOT_THST_EXPO 0.649999976158142090 9 +1 1 MOT_THST_HOVER 0.500000000000000000 9 +1 1 MOT_YAW_HEADROOM 200 4 +1 1 NTF_BUZZ_ENABLE 0 2 +1 1 NTF_LED_BRIGHT 3 2 +1 1 NTF_LED_OVERRIDE 0 2 +1 1 PHLD_BRAKE_ANGLE 3000 4 +1 1 PHLD_BRAKE_RATE 8 4 +1 1 PILOT_ACCEL_Z 250 4 +1 1 PILOT_THR_BHV 0 4 +1 1 PILOT_THR_FILT 0.000000000000000000 9 +1 1 PILOT_TKOFF_ALT 0.000000000000000000 9 +1 1 PILOT_TKOFF_DZ 100 4 +1 1 PILOT_VELZ_MAX 250 4 +1 1 PLND_ENABLED 0 2 +1 1 POS_XY_P 1.000000000000000000 9 +1 1 POS_Z_P 1.000000000000000000 9 +1 1 PSC_ACC_XY_FILT 2.000000000000000000 9 +1 1 RALLY_INCL_HOME 1 2 +1 1 RALLY_LIMIT_KM 0.300000011920928955 9 +1 1 RALLY_TOTAL 0 2 +1 1 RC10_DZ 0 4 +1 1 RC10_FUNCTION 0 2 +1 1 RC10_MAX 2000 4 +1 1 RC10_MIN 1000 4 +1 1 RC10_REV 1 2 +1 1 RC10_TRIM 1500 4 +1 1 RC11_DZ 0 4 +1 1 RC11_FUNCTION 0 2 +1 1 RC11_MAX 2000 4 +1 1 RC11_MIN 1000 4 +1 1 RC11_REV 1 2 +1 1 RC11_TRIM 1500 4 +1 1 RC12_DZ 0 4 +1 1 RC12_FUNCTION 0 2 +1 1 RC12_MAX 2000 4 +1 1 RC12_MIN 1000 4 +1 1 RC12_REV 1 2 +1 1 RC12_TRIM 1500 4 +1 1 RC13_DZ 0 4 +1 1 RC13_FUNCTION 0 2 +1 1 RC13_MAX 2000 4 +1 1 RC13_MIN 1000 4 +1 1 RC13_REV 1 2 +1 1 RC13_TRIM 1500 4 +1 1 RC14_DZ 0 4 +1 1 RC14_FUNCTION 0 2 +1 1 RC14_MAX 2000 4 +1 1 RC14_MIN 1000 4 +1 1 RC14_REV 1 2 +1 1 RC14_TRIM 1500 4 +1 1 RC1_DZ 30 4 +1 1 RC1_MAX 2006 4 +1 1 RC1_MIN 982 4 +1 1 RC1_REV 1 2 +1 1 RC1_TRIM 1495 4 +1 1 RC2_DZ 30 4 +1 1 RC2_MAX 2006 4 +1 1 RC2_MIN 982 4 +1 1 RC2_REV 1 2 +1 1 RC2_TRIM 1494 4 +1 1 RC3_DZ 30 4 +1 1 RC3_MAX 2006 4 +1 1 RC3_MIN 982 4 +1 1 RC3_REV 1 2 +1 1 RC3_TRIM 982 4 +1 1 RC4_DZ 40 4 +1 1 RC4_MAX 2006 4 +1 1 RC4_MIN 982 4 +1 1 RC4_REV 1 2 +1 1 RC4_TRIM 1494 4 +1 1 RC5_DZ 0 4 +1 1 RC5_FUNCTION 0 2 +1 1 RC5_MAX 2000 4 +1 1 RC5_MIN 1000 4 +1 1 RC5_REV 1 2 +1 1 RC5_TRIM 1500 4 +1 1 RC6_DZ 0 4 +1 1 RC6_FUNCTION 0 2 +1 1 RC6_MAX 2000 4 +1 1 RC6_MIN 1000 4 +1 1 RC6_REV 1 2 +1 1 RC6_TRIM 1500 4 +1 1 RC7_DZ 0 4 +1 1 RC7_FUNCTION 0 2 +1 1 RC7_MAX 2000 4 +1 1 RC7_MIN 1000 4 +1 1 RC7_REV 1 2 +1 1 RC7_TRIM 1500 4 +1 1 RC8_DZ 0 4 +1 1 RC8_FUNCTION 0 2 +1 1 RC8_MAX 2000 4 +1 1 RC8_MIN 1000 4 +1 1 RC8_REV 1 2 +1 1 RC8_TRIM 1500 4 +1 1 RC9_DZ 0 4 +1 1 RC9_FUNCTION 0 2 +1 1 RC9_MAX 2000 4 +1 1 RC9_MIN 1000 4 +1 1 RC9_REV 1 2 +1 1 RC9_TRIM 1500 4 +1 1 RCMAP_PITCH 2 2 +1 1 RCMAP_ROLL 1 2 +1 1 RCMAP_THROTTLE 3 2 +1 1 RCMAP_YAW 4 2 +1 1 RC_FEEL_RP 50 2 +1 1 RC_SPEED 490 4 +1 1 RELAY_DEFAULT 0 2 +1 1 RELAY_PIN -1 2 +1 1 RELAY_PIN2 -1 2 +1 1 RELAY_PIN3 -1 2 +1 1 RELAY_PIN4 -1 2 +1 1 RNGFND2_ADDR 0 2 +1 1 RNGFND2_FUNCTION 0 2 +1 1 RNGFND2_GNDCLEAR 10 2 +1 1 RNGFND2_MAX_CM 700 4 +1 1 RNGFND2_MIN_CM 20 4 +1 1 RNGFND2_OFFSET 0.000000000000000000 9 +1 1 RNGFND2_PIN -1 2 +1 1 RNGFND2_RMETRIC 1 2 +1 1 RNGFND2_SCALING 3.000000000000000000 9 +1 1 RNGFND2_SETTLE 0 4 +1 1 RNGFND2_STOP_PIN -1 2 +1 1 RNGFND2_TYPE 0 2 +1 1 RNGFND_ADDR 0 2 +1 1 RNGFND_FUNCTION 0 2 +1 1 RNGFND_GAIN 0.800000011920928955 9 +1 1 RNGFND_GNDCLEAR 10 2 +1 1 RNGFND_MAX_CM 700 4 +1 1 RNGFND_MIN_CM 20 4 +1 1 RNGFND_OFFSET 0.000000000000000000 9 +1 1 RNGFND_PIN -1 2 +1 1 RNGFND_PWRRNG 0 4 +1 1 RNGFND_RMETRIC 1 2 +1 1 RNGFND_SCALING 3.000000000000000000 9 +1 1 RNGFND_SETTLE 0 4 +1 1 RNGFND_STOP_PIN -1 2 +1 1 RNGFND_TYPE 0 2 +1 1 RPM2_SCALING 1.000000000000000000 9 +1 1 RPM2_TYPE 0 2 +1 1 RPM_MAX 100000.000000000000000000 9 +1 1 RPM_MIN 10.000000000000000000 9 +1 1 RPM_MIN_QUAL 0.500000000000000000 9 +1 1 RPM_SCALING 1.000000000000000000 9 +1 1 RPM_TYPE 0 2 +1 1 RSSI_ANA_PIN 11 2 +1 1 RSSI_CHANNEL 0 2 +1 1 RSSI_CHAN_HIGH 2000 4 +1 1 RSSI_CHAN_LOW 1000 4 +1 1 RSSI_PIN_HIGH 3.299999952316284180 9 +1 1 RSSI_PIN_LOW 0.000000000000000000 9 +1 1 RSSI_TYPE 1 2 +1 1 RTL_ALT 2000 4 +1 1 RTL_ALT_FINAL 0 4 +1 1 RTL_CLIMB_MIN 0 4 +1 1 RTL_CONE_SLOPE 3.000000000000000000 9 +1 1 RTL_LOIT_TIME 5000 6 +1 1 RTL_SPEED 0 4 +1 1 SCHED_DEBUG 0 2 +1 1 SCHED_LOOP_RATE 400 4 +1 1 SERIAL0_BAUD 115 6 +1 1 SERIAL0_PROTOCOL 1 2 +1 1 SERIAL1_BAUD 57 6 +1 1 SERIAL1_PROTOCOL 1 2 +1 1 SERIAL2_BAUD 9 6 +1 1 SERIAL2_PROTOCOL 3 2 +1 1 SERIAL3_BAUD 38 6 +1 1 SERIAL3_PROTOCOL 5 2 +1 1 SERIAL4_BAUD 38 6 +1 1 SERIAL4_PROTOCOL 5 2 +1 1 SERIAL5_BAUD 921600 6 +1 1 SERIAL5_PROTOCOL 1 2 +1 1 SIMPLE 0 2 +1 1 SR0_ADSB 5 4 +1 1 SR0_EXTRA1 0 4 +1 1 SR0_EXTRA2 0 4 +1 1 SR0_EXTRA3 0 4 +1 1 SR0_EXT_STAT 0 4 +1 1 SR0_PARAMS 0 4 +1 1 SR0_POSITION 0 4 +1 1 SR0_RAW_CTRL 0 4 +1 1 SR0_RAW_SENS 0 4 +1 1 SR0_RC_CHAN 0 4 +1 1 SR1_ADSB 5 4 +1 1 SR1_EXTRA1 0 4 +1 1 SR1_EXTRA2 0 4 +1 1 SR1_EXTRA3 0 4 +1 1 SR1_EXT_STAT 0 4 +1 1 SR1_PARAMS 0 4 +1 1 SR1_POSITION 0 4 +1 1 SR1_RAW_CTRL 0 4 +1 1 SR1_RAW_SENS 0 4 +1 1 SR1_RC_CHAN 0 4 +1 1 SR2_ADSB 5 4 +1 1 SR2_EXTRA1 10 4 +1 1 SR2_EXTRA2 10 4 +1 1 SR2_EXTRA3 3 4 +1 1 SR2_EXT_STAT 2 4 +1 1 SR2_PARAMS 10 4 +1 1 SR2_POSITION 3 4 +1 1 SR2_RAW_CTRL 0 4 +1 1 SR2_RAW_SENS 2 4 +1 1 SR2_RC_CHAN 2 4 +1 1 SR3_ADSB 5 4 +1 1 SR3_EXTRA1 0 4 +1 1 SR3_EXTRA2 0 4 +1 1 SR3_EXTRA3 0 4 +1 1 SR3_EXT_STAT 0 4 +1 1 SR3_PARAMS 0 4 +1 1 SR3_POSITION 0 4 +1 1 SR3_RAW_CTRL 0 4 +1 1 SR3_RAW_SENS 0 4 +1 1 SR3_RC_CHAN 0 4 +1 1 SUPER_SIMPLE 0 2 +1 1 SYSID_MYGCS 255 4 +1 1 SYSID_SW_MREV 120 4 +1 1 SYSID_SW_TYPE 10 2 +1 1 SYSID_THISMAV 1 4 +1 1 TELEM_DELAY 0 2 +1 1 TERRAIN_ENABLE 1 2 +1 1 TERRAIN_FOLLOW 0 2 +1 1 TERRAIN_SPACING 100 4 +1 1 THROW_MOT_START 0 2 +1 1 THROW_NEXTMODE 18 2 +1 1 THROW_TYPE 0 2 +1 1 THR_DZ 50 4 +1 1 TUNE 0 2 +1 1 TUNE_HIGH 1000 4 +1 1 TUNE_LOW 0 4 +1 1 VEL_XY_FILT_HZ 5.000000000000000000 9 +1 1 VEL_XY_I 0.500000000000000000 9 +1 1 VEL_XY_IMAX 1000.000000000000000000 9 +1 1 VEL_XY_P 1.000000000000000000 9 +1 1 VEL_Z_P 5.000000000000000000 9 +1 1 WPNAV_ACCEL 250.000000000000000000 9 +1 1 WPNAV_ACCEL_Z 100.000000000000000000 9 +1 1 WPNAV_LOIT_JERK 1000.000000000000000000 9 +1 1 WPNAV_LOIT_MAXA 250.000000000000000000 9 +1 1 WPNAV_LOIT_MINA 25.000000000000000000 9 +1 1 WPNAV_LOIT_SPEED 1000.000000000000000000 9 +1 1 WPNAV_RADIUS 200.000000000000000000 9 +1 1 WPNAV_RFND_USE 1 2 +1 1 WPNAV_SPEED 650.000000000000000000 9 +1 1 WPNAV_SPEED_DN 150.000000000000000000 9 +1 1 WPNAV_SPEED_UP 250.000000000000000000 9 +1 1 WP_NAVALT_MIN 0.000000000000000000 9 +1 1 WP_YAW_BEHAVIOR 2 2 \ No newline at end of file diff --git a/src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml b/src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml index 16617acf106a2f10c23fc3392d18bca3b6ca8ef9..120221ee39845ec0a81c505a25d10538b51bdc9f 100644 --- a/src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml +++ b/src/FirmwarePlugin/APM/CopterGeoFenceEditor.qml @@ -36,11 +36,6 @@ Column { color: qgcPal.text } - QGCLabel { - text: qsTr("Must be connected to Vehicle to change fence settings.") - visible: !QGroundControl.multiVehicleManager.activeVehicle - } - Repeater { model: geoFenceController.params @@ -80,7 +75,7 @@ Column { anchors.left: parent.left anchors.right: parent.right flightMap: editorMap - polygon: root.polygon + polygon: geoFenceController.polygon sectionLabel: qsTr("Fence Polygon:") visible: geoFenceController.polygonSupported } diff --git a/src/FirmwarePlugin/APM/Plane3.7.OfflineEditing.params b/src/FirmwarePlugin/APM/Plane3.7.OfflineEditing.params new file mode 100644 index 0000000000000000000000000000000000000000..53cafb3746c800524ec9623da2dd7c182c42e144 --- /dev/null +++ b/src/FirmwarePlugin/APM/Plane3.7.OfflineEditing.params @@ -0,0 +1,663 @@ +# Onboard parameters for vehicle 1 +# +# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT) +1 1 ACRO_LOCKING 0 2 +1 1 ACRO_PITCH_RATE 180 4 +1 1 ACRO_ROLL_RATE 180 4 +1 1 ADSB_ENABLE 0 2 +1 1 AFS_ENABLE 0 2 +1 1 AHRS_COMP_BETA 0.100000001490116119 9 +1 1 AHRS_EKF_TYPE 2 2 +1 1 AHRS_GPS_GAIN 1.000000000000000000 9 +1 1 AHRS_GPS_MINSATS 6 2 +1 1 AHRS_GPS_USE 1 2 +1 1 AHRS_ORIENTATION 0 2 +1 1 AHRS_RP_P 0.200000002980232239 9 +1 1 AHRS_TRIM_X 0.000000000000000000 9 +1 1 AHRS_TRIM_Y 0.000000000000000000 9 +1 1 AHRS_TRIM_Z 0.000000000000000000 9 +1 1 AHRS_WIND_MAX 0 2 +1 1 AHRS_YAW_P 0.200000002980232239 9 +1 1 ALT_CTRL_ALG 0 2 +1 1 ALT_HOLD_FBWCM 0 4 +1 1 ALT_HOLD_RTL 10000 6 +1 1 ALT_MIX 1.000000000000000000 9 +1 1 ALT_OFFSET 0 4 +1 1 ARMING_ACCTHRESH 0.750000000000000000 9 +1 1 ARMING_CHECK 1 4 +1 1 ARMING_MIN_VOLT 0.000000000000000000 9 +1 1 ARMING_MIN_VOLT2 0.000000000000000000 9 +1 1 ARMING_REQUIRE 1 2 +1 1 ARMING_RUDDER 1 2 +1 1 ARSPD_AUTOCAL 0 2 +1 1 ARSPD_ENABLE 1 2 +1 1 ARSPD_FBW_MAX 22 4 +1 1 ARSPD_FBW_MIN 9 4 +1 1 ARSPD_OFFSET 2.770258665084838867 9 +1 1 ARSPD_PIN 15 2 +1 1 ARSPD_PSI_RANGE 1.000000000000000000 9 +1 1 ARSPD_RATIO 1.993600010871887207 9 +1 1 ARSPD_SKIP_CAL 0 2 +1 1 ARSPD_TUBE_ORDER 2 2 +1 1 ARSPD_USE 0 2 +1 1 AUTOTUNE_LEVEL 6 2 +1 1 AUTO_FBW_STEER 0 2 +1 1 AVD_ENABLE 0 2 +1 1 BATT2_AMP_OFFSET 0.000000000000000000 9 +1 1 BATT2_AMP_PERVOL 17.000000000000000000 9 +1 1 BATT2_CAPACITY 3300 6 +1 1 BATT2_CURR_PIN 3 2 +1 1 BATT2_MONITOR 0 2 +1 1 BATT2_VOLT_MULT 10.100000381469726562 9 +1 1 BATT2_VOLT_PIN 2 2 +1 1 BATT2_WATT_MAX 0 4 +1 1 BATT_AMP_OFFSET 0.000000000000000000 9 +1 1 BATT_AMP_PERVOLT 17.000000000000000000 9 +1 1 BATT_CAPACITY 3300 6 +1 1 BATT_CURR_PIN 3 2 +1 1 BATT_MONITOR 0 2 +1 1 BATT_VOLT_MULT 10.100000381469726562 9 +1 1 BATT_VOLT_PIN 2 2 +1 1 BATT_WATT_MAX 0 4 +1 1 BRD_CAN_ENABLE 0 2 +1 1 BRD_IMU_TARGTEMP -1 2 +1 1 BRD_PWM_COUNT 4 2 +1 1 BRD_SAFETYENABLE 1 2 +1 1 BRD_SAFETY_MASK 0 6 +1 1 BRD_SBUS_OUT 0 2 +1 1 BRD_SER1_RTSCTS 2 2 +1 1 BRD_SER2_RTSCTS 2 2 +1 1 BRD_SERIAL_NUM 0 4 +1 1 BRD_TYPE 2 2 +1 1 BTN_ENABLE 0 2 +1 1 CAM_DURATION 10 2 +1 1 CAM_FEEDBACK_PIN -1 2 +1 1 CAM_FEEDBACK_POL 1 2 +1 1 CAM_MAX_ROLL 0 4 +1 1 CAM_MIN_INTERVAL 0 4 +1 1 CAM_RELAY_ON 1 2 +1 1 CAM_SERVO_OFF 1100 4 +1 1 CAM_SERVO_ON 1300 4 +1 1 CAM_TRIGG_DIST 0.000000000000000000 9 +1 1 CAM_TRIGG_TYPE 0 2 +1 1 CHUTE_CHAN 0 2 +1 1 CHUTE_ENABLED 0 2 +1 1 CLI_ENABLED 0 2 +1 1 COMPASS_AUTODEC 1 2 +1 1 COMPASS_CAL_FIT 8.000000000000000000 9 +1 1 COMPASS_DEC 0.000000000000000000 9 +1 1 COMPASS_DEV_ID 131594 6 +1 1 COMPASS_DEV_ID2 0 6 +1 1 COMPASS_DEV_ID3 0 6 +1 1 COMPASS_DIA2_X 0.000000000000000000 9 +1 1 COMPASS_DIA2_Y 0.000000000000000000 9 +1 1 COMPASS_DIA2_Z 0.000000000000000000 9 +1 1 COMPASS_DIA3_X 0.000000000000000000 9 +1 1 COMPASS_DIA3_Y 0.000000000000000000 9 +1 1 COMPASS_DIA3_Z 0.000000000000000000 9 +1 1 COMPASS_DIA_X 1.000000000000000000 9 +1 1 COMPASS_DIA_Y 1.000000000000000000 9 +1 1 COMPASS_DIA_Z 1.000000000000000000 9 +1 1 COMPASS_EXTERN2 0 2 +1 1 COMPASS_EXTERN3 0 2 +1 1 COMPASS_EXTERNAL 0 2 +1 1 COMPASS_LEARN 1 2 +1 1 COMPASS_MOT2_X 0.000000000000000000 9 +1 1 COMPASS_MOT2_Y 0.000000000000000000 9 +1 1 COMPASS_MOT2_Z 0.000000000000000000 9 +1 1 COMPASS_MOT3_X 0.000000000000000000 9 +1 1 COMPASS_MOT3_Y 0.000000000000000000 9 +1 1 COMPASS_MOT3_Z 0.000000000000000000 9 +1 1 COMPASS_MOTCT 0 2 +1 1 COMPASS_MOT_X 0.000000000000000000 9 +1 1 COMPASS_MOT_Y 0.000000000000000000 9 +1 1 COMPASS_MOT_Z 0.000000000000000000 9 +1 1 COMPASS_ODI2_X 0.000000000000000000 9 +1 1 COMPASS_ODI2_Y 0.000000000000000000 9 +1 1 COMPASS_ODI2_Z 0.000000000000000000 9 +1 1 COMPASS_ODI3_X 0.000000000000000000 9 +1 1 COMPASS_ODI3_Y 0.000000000000000000 9 +1 1 COMPASS_ODI3_Z 0.000000000000000000 9 +1 1 COMPASS_ODI_X 0.000000000000000000 9 +1 1 COMPASS_ODI_Y 0.000000000000000000 9 +1 1 COMPASS_ODI_Z 0.000000000000000000 9 +1 1 COMPASS_OFS2_X 0.000000000000000000 9 +1 1 COMPASS_OFS2_Y 0.000000000000000000 9 +1 1 COMPASS_OFS2_Z 0.000000000000000000 9 +1 1 COMPASS_OFS3_X 0.000000000000000000 9 +1 1 COMPASS_OFS3_Y 0.000000000000000000 9 +1 1 COMPASS_OFS3_Z 0.000000000000000000 9 +1 1 COMPASS_OFS_X 0.000000000000000000 9 +1 1 COMPASS_OFS_Y 0.000000000000000000 9 +1 1 COMPASS_OFS_Z 0.000000000000000000 9 +1 1 COMPASS_ORIENT 0 2 +1 1 COMPASS_ORIENT2 0 2 +1 1 COMPASS_ORIENT3 0 2 +1 1 COMPASS_PRIMARY 0 2 +1 1 COMPASS_USE 1 2 +1 1 COMPASS_USE2 1 2 +1 1 COMPASS_USE3 1 2 +1 1 CRASH_ACC_THRESH 0 2 +1 1 CRASH_DETECT 0 2 +1 1 DSPOILR_RUD_RATE 100 4 +1 1 EK2_ABIAS_P_NSE 0.004999999888241291 9 +1 1 EK2_ACC_P_NSE 0.600000023841857910 9 +1 1 EK2_ALT_M_NSE 3.000000000000000000 9 +1 1 EK2_ALT_SOURCE 0 2 +1 1 EK2_CHECK_SCALE 150 4 +1 1 EK2_EAS_I_GATE 400 4 +1 1 EK2_EAS_M_NSE 1.399999976158142090 9 +1 1 EK2_ENABLE 1 2 +1 1 EK2_FLOW_DELAY 10 2 +1 1 EK2_FLOW_I_GATE 300 4 +1 1 EK2_FLOW_M_NSE 0.250000000000000000 9 +1 1 EK2_GBIAS_P_NSE 0.000099999997473788 9 +1 1 EK2_GLITCH_RAD 25 2 +1 1 EK2_GPS_CHECK 31 2 +1 1 EK2_GPS_DELAY 220 4 +1 1 EK2_GPS_TYPE 0 2 +1 1 EK2_GSCL_P_NSE 0.000500000023748726 9 +1 1 EK2_GYRO_P_NSE 0.029999999329447746 9 +1 1 EK2_HGT_DELAY 60 4 +1 1 EK2_HGT_I_GATE 500 4 +1 1 EK2_IMU_MASK 3 2 +1 1 EK2_LOG_MASK 1 2 +1 1 EK2_MAGB_P_NSE 0.000099999997473788 9 +1 1 EK2_MAGE_P_NSE 0.001000000047497451 9 +1 1 EK2_MAG_CAL 0 2 +1 1 EK2_MAG_I_GATE 300 4 +1 1 EK2_MAG_M_NSE 0.050000000745058060 9 +1 1 EK2_MAX_FLOW 2.500000000000000000 9 +1 1 EK2_NOAID_M_NSE 10.000000000000000000 9 +1 1 EK2_POSNE_M_NSE 1.000000000000000000 9 +1 1 EK2_POS_I_GATE 500 4 +1 1 EK2_RNG_I_GATE 500 4 +1 1 EK2_RNG_M_NSE 0.500000000000000000 9 +1 1 EK2_RNG_USE_HGT -1 2 +1 1 EK2_TAU_OUTPUT 25 2 +1 1 EK2_VELD_M_NSE 0.699999988079071045 9 +1 1 EK2_VELNE_M_NSE 0.500000000000000000 9 +1 1 EK2_VEL_I_GATE 500 4 +1 1 EK2_WIND_PSCALE 0.500000000000000000 9 +1 1 EK2_WIND_P_NSE 0.100000001490116119 9 +1 1 EK2_YAW_I_GATE 300 4 +1 1 EK2_YAW_M_NSE 0.500000000000000000 9 +1 1 EKF_ENABLE 0 2 +1 1 ELEVON_CH1_REV 0 2 +1 1 ELEVON_CH2_REV 0 2 +1 1 ELEVON_MIXING 0 2 +1 1 ELEVON_OUTPUT 0 2 +1 1 ELEVON_REVERSE 0 2 +1 1 FBWA_TDRAG_CHAN 0 2 +1 1 FBWB_CLIMB_RATE 2 2 +1 1 FBWB_ELEV_REV 0 2 +1 1 FENCE_ACTION 0 2 +1 1 FENCE_AUTOENABLE 0 2 +1 1 FENCE_CHANNEL 0 2 +1 1 FENCE_MAXALT 0 4 +1 1 FENCE_MINALT 0 4 +1 1 FENCE_RETALT 0 4 +1 1 FENCE_RET_RALLY 0 2 +1 1 FENCE_TOTAL 0 2 +1 1 FLAPERON_OUTPUT 0 2 +1 1 FLAP_1_PERCNT 0 2 +1 1 FLAP_1_SPEED 0 2 +1 1 FLAP_2_PERCNT 0 2 +1 1 FLAP_2_SPEED 0 2 +1 1 FLAP_IN_CHANNEL 0 2 +1 1 FLAP_SLEWRATE 75 2 +1 1 FLOW_ENABLE 0 2 +1 1 FLOW_FXSCALER 0 4 +1 1 FLOW_FYSCALER 0 4 +1 1 FLOW_ORIENT_YAW 0 4 +1 1 FLTMODE1 11 2 +1 1 FLTMODE2 11 2 +1 1 FLTMODE3 5 2 +1 1 FLTMODE4 5 2 +1 1 FLTMODE5 0 2 +1 1 FLTMODE6 0 2 +1 1 FLTMODE_CH 8 2 +1 1 FORMAT_VERSION 13 4 +1 1 FS_BATT_MAH 0.000000000000000000 9 +1 1 FS_BATT_VOLTAGE 0.000000000000000000 9 +1 1 FS_GCS_ENABL 0 2 +1 1 FS_LONG_ACTN 0 2 +1 1 FS_LONG_TIMEOUT 5.000000000000000000 9 +1 1 FS_SHORT_ACTN 0 2 +1 1 FS_SHORT_TIMEOUT 1.500000000000000000 9 +1 1 GCS_PID_MASK 0 4 +1 1 GLIDE_SLOPE_MIN 15 4 +1 1 GLIDE_SLOPE_THR 5.000000000000000000 9 +1 1 GND_ABS_PRESS 101321.710937500000000000 9 +1 1 GND_ALT_OFFSET 0.000000000000000000 9 +1 1 GND_PRIMARY 0 2 +1 1 GND_TEMP 25.000000000000000000 9 +1 1 GPS_AUTO_CONFIG 1 2 +1 1 GPS_AUTO_SWITCH 1 2 +1 1 GPS_GNSS_MODE 0 2 +1 1 GPS_GNSS_MODE2 0 2 +1 1 GPS_INJECT_TO 127 2 +1 1 GPS_MIN_DGPS 100 2 +1 1 GPS_MIN_ELEV -100 2 +1 1 GPS_NAVFILTER 8 2 +1 1 GPS_RAW_DATA 0 2 +1 1 GPS_SAVE_CFG 0 2 +1 1 GPS_SBAS_MODE 2 2 +1 1 GPS_SBP_LOGMASK -256 4 +1 1 GPS_TYPE 1 2 +1 1 GPS_TYPE2 0 2 +1 1 GROUND_STEER_ALT 0.000000000000000000 9 +1 1 GROUND_STEER_DPS 90 4 +1 1 HIL_ERR_LIMIT 5.000000000000000000 9 +1 1 HIL_MODE 0 2 +1 1 HIL_SERVOS 0 2 +1 1 ICE_ENABLE 0 2 +1 1 INITIAL_MODE 0 2 +1 1 INS_ACC2OFFS_X 0.000000000000000000 9 +1 1 INS_ACC2OFFS_Y 0.000000000000000000 9 +1 1 INS_ACC2OFFS_Z 0.000000000000000000 9 +1 1 INS_ACC2SCAL_X 1.000000000000000000 9 +1 1 INS_ACC2SCAL_Y 1.000000000000000000 9 +1 1 INS_ACC2SCAL_Z 1.000000000000000000 9 +1 1 INS_ACC3OFFS_X 0.000000000000000000 9 +1 1 INS_ACC3OFFS_Y 0.000000000000000000 9 +1 1 INS_ACC3OFFS_Z 0.000000000000000000 9 +1 1 INS_ACC3SCAL_X 0.000000000000000000 9 +1 1 INS_ACC3SCAL_Y 0.000000000000000000 9 +1 1 INS_ACC3SCAL_Z 0.000000000000000000 9 +1 1 INS_ACCEL_FILTER 20 2 +1 1 INS_ACCOFFS_X 0.000000000000000000 9 +1 1 INS_ACCOFFS_Y 0.000000000000000000 9 +1 1 INS_ACCOFFS_Z 0.000000000000000000 9 +1 1 INS_ACCSCAL_X 1.000000000000000000 9 +1 1 INS_ACCSCAL_Y 1.000000000000000000 9 +1 1 INS_ACCSCAL_Z 1.000000000000000000 9 +1 1 INS_ACC_BODYFIX 2 2 +1 1 INS_GYR2OFFS_X 0.000000000000000000 9 +1 1 INS_GYR2OFFS_Y 0.000000000000000000 9 +1 1 INS_GYR2OFFS_Z 0.000000000000000000 9 +1 1 INS_GYR3OFFS_X 0.000000000000000000 9 +1 1 INS_GYR3OFFS_Y 0.000000000000000000 9 +1 1 INS_GYR3OFFS_Z 0.000000000000000000 9 +1 1 INS_GYROFFS_X 0.000000000000000000 9 +1 1 INS_GYROFFS_Y 0.000000000000000000 9 +1 1 INS_GYROFFS_Z 0.000000000000000000 9 +1 1 INS_GYRO_FILTER 20 2 +1 1 INS_GYR_CAL 1 2 +1 1 INS_PRODUCT_ID 5 4 +1 1 INS_STILL_THRESH 0.100000001490116119 9 +1 1 INS_TRIM_OPTION 1 2 +1 1 INS_USE 1 2 +1 1 INS_USE2 1 2 +1 1 INS_USE3 0 2 +1 1 INVERTEDFLT_CH 0 2 +1 1 KFF_RDDRMIX 0.500000000000000000 9 +1 1 KFF_THR2PTCH 0.000000000000000000 9 +1 1 LAND_ABORT_DEG 0.000000000000000000 9 +1 1 LAND_ABORT_THR 0 2 +1 1 LAND_DISARMDELAY 20 2 +1 1 LAND_FLAP_PERCNT 0 2 +1 1 LAND_FLARE_ALT 3.000000000000000000 9 +1 1 LAND_FLARE_SEC 2.000000000000000000 9 +1 1 LAND_PF_ALT 10.000000000000000000 9 +1 1 LAND_PF_ARSPD 0.000000000000000000 9 +1 1 LAND_PF_SEC 6.000000000000000000 9 +1 1 LAND_PITCH_CD 0 4 +1 1 LAND_SLOPE_RCALC 2.000000000000000000 9 +1 1 LAND_THEN_NEUTRL 0 2 +1 1 LAND_THR_SLEW 0 2 +1 1 LEVEL_ROLL_LIMIT 5 2 +1 1 LIM_PITCH_MAX 2000 4 +1 1 LIM_PITCH_MIN -2500 4 +1 1 LIM_ROLL_CD 4500 4 +1 1 LOG_BACKEND_TYPE 1 2 +1 1 LOG_BITMASK 65535 6 +1 1 LOG_DISARMED 0 2 +1 1 LOG_FILE_BUFSIZE 16 2 +1 1 LOG_REPLAY 0 2 +1 1 MAG_ENABLE 1 2 +1 1 MIN_GNDSPD_CM 0 6 +1 1 MIS_RESTART 0 2 +1 1 MIS_TOTAL 0 4 +1 1 MIXING_GAIN 0.500000000000000000 9 +1 1 MIXING_OFFSET 0 4 +1 1 MNT_ANGMAX_PAN 4500 4 +1 1 MNT_ANGMAX_ROL 4500 4 +1 1 MNT_ANGMAX_TIL 4500 4 +1 1 MNT_ANGMIN_PAN -4500 4 +1 1 MNT_ANGMIN_ROL -4500 4 +1 1 MNT_ANGMIN_TIL -4500 4 +1 1 MNT_DEFLT_MODE 3 2 +1 1 MNT_JSTICK_SPD 0 2 +1 1 MNT_LEAD_PTCH 0.000000000000000000 9 +1 1 MNT_LEAD_RLL 0.000000000000000000 9 +1 1 MNT_NEUTRAL_X 0.000000000000000000 9 +1 1 MNT_NEUTRAL_Y 0.000000000000000000 9 +1 1 MNT_NEUTRAL_Z 0.000000000000000000 9 +1 1 MNT_RC_IN_PAN 0 2 +1 1 MNT_RC_IN_ROLL 0 2 +1 1 MNT_RC_IN_TILT 0 2 +1 1 MNT_RETRACT_X 0.000000000000000000 9 +1 1 MNT_RETRACT_Y 0.000000000000000000 9 +1 1 MNT_RETRACT_Z 0.000000000000000000 9 +1 1 MNT_STAB_PAN 0 2 +1 1 MNT_STAB_ROLL 0 2 +1 1 MNT_STAB_TILT 0 2 +1 1 MNT_TYPE 0 2 +1 1 NAVL1_DAMPING 0.750000000000000000 9 +1 1 NAVL1_PERIOD 20.000000000000000000 9 +1 1 NAVL1_XTRACK_I 0.019999999552965164 9 +1 1 NAV_CONTROLLER 1 2 +1 1 NTF_BUZZ_ENABLE 1 2 +1 1 NTF_LED_BRIGHT 3 2 +1 1 NTF_LED_OVERRIDE 0 2 +1 1 OVERRIDE_CHAN 0 2 +1 1 OVERRIDE_SAFETY 1 2 +1 1 PTCH2SRV_D 0.019999999552965164 9 +1 1 PTCH2SRV_FF 0.000000000000000000 9 +1 1 PTCH2SRV_I 0.150000005960464478 9 +1 1 PTCH2SRV_IMAX 3000 4 +1 1 PTCH2SRV_P 0.600000023841857910 9 +1 1 PTCH2SRV_RLL 1.000000000000000000 9 +1 1 PTCH2SRV_RMAX_DN 0 4 +1 1 PTCH2SRV_RMAX_UP 0 4 +1 1 PTCH2SRV_TCONST 0.500000000000000000 9 +1 1 Q_ENABLE 0 2 +1 1 RALLY_INCL_HOME 0 2 +1 1 RALLY_LIMIT_KM 5.000000000000000000 9 +1 1 RALLY_TOTAL 0 2 +1 1 RC10_DZ 0 4 +1 1 RC10_FUNCTION 0 2 +1 1 RC10_MAX 1900 4 +1 1 RC10_MIN 1100 4 +1 1 RC10_REV 1 2 +1 1 RC10_TRIM 1500 4 +1 1 RC11_DZ 0 4 +1 1 RC11_FUNCTION 0 2 +1 1 RC11_MAX 1900 4 +1 1 RC11_MIN 1100 4 +1 1 RC11_REV 1 2 +1 1 RC11_TRIM 1500 4 +1 1 RC12_DZ 0 4 +1 1 RC12_FUNCTION 0 2 +1 1 RC12_MAX 1900 4 +1 1 RC12_MIN 1100 4 +1 1 RC12_REV 1 2 +1 1 RC12_TRIM 1500 4 +1 1 RC13_DZ 0 4 +1 1 RC13_FUNCTION 0 2 +1 1 RC13_MAX 1900 4 +1 1 RC13_MIN 1100 4 +1 1 RC13_REV 1 2 +1 1 RC13_TRIM 1500 4 +1 1 RC14_DZ 0 4 +1 1 RC14_FUNCTION 0 2 +1 1 RC14_MAX 1900 4 +1 1 RC14_MIN 1100 4 +1 1 RC14_REV 1 2 +1 1 RC14_TRIM 1500 4 +1 1 RC15_DZ 0 4 +1 1 RC15_FUNCTION 0 2 +1 1 RC15_MAX 1900 4 +1 1 RC15_MIN 1100 4 +1 1 RC15_REV 1 2 +1 1 RC15_TRIM 1500 4 +1 1 RC16_DZ 0 4 +1 1 RC16_FUNCTION 0 2 +1 1 RC16_MAX 1900 4 +1 1 RC16_MIN 1100 4 +1 1 RC16_REV 1 2 +1 1 RC16_TRIM 1500 4 +1 1 RC1_DZ 30 4 +1 1 RC1_MAX 1900 4 +1 1 RC1_MIN 1100 4 +1 1 RC1_REV 1 2 +1 1 RC1_TRIM 1500 4 +1 1 RC2_DZ 30 4 +1 1 RC2_MAX 1900 4 +1 1 RC2_MIN 1100 4 +1 1 RC2_REV 1 2 +1 1 RC2_TRIM 1500 4 +1 1 RC3_DZ 30 4 +1 1 RC3_MAX 1900 4 +1 1 RC3_MIN 1100 4 +1 1 RC3_REV 1 2 +1 1 RC3_TRIM 1100 4 +1 1 RC4_DZ 30 4 +1 1 RC4_MAX 1900 4 +1 1 RC4_MIN 1100 4 +1 1 RC4_REV 1 2 +1 1 RC4_TRIM 1500 4 +1 1 RC5_DZ 0 4 +1 1 RC5_FUNCTION 0 2 +1 1 RC5_MAX 1900 4 +1 1 RC5_MIN 1100 4 +1 1 RC5_REV 1 2 +1 1 RC5_TRIM 1500 4 +1 1 RC6_DZ 0 4 +1 1 RC6_FUNCTION 0 2 +1 1 RC6_MAX 1900 4 +1 1 RC6_MIN 1100 4 +1 1 RC6_REV 1 2 +1 1 RC6_TRIM 1500 4 +1 1 RC7_DZ 0 4 +1 1 RC7_FUNCTION 0 2 +1 1 RC7_MAX 1900 4 +1 1 RC7_MIN 1100 4 +1 1 RC7_REV 1 2 +1 1 RC7_TRIM 1500 4 +1 1 RC8_DZ 0 4 +1 1 RC8_FUNCTION 0 2 +1 1 RC8_MAX 1900 4 +1 1 RC8_MIN 1100 4 +1 1 RC8_REV 1 2 +1 1 RC8_TRIM 1500 4 +1 1 RC9_DZ 0 4 +1 1 RC9_FUNCTION 0 2 +1 1 RC9_MAX 1900 4 +1 1 RC9_MIN 1100 4 +1 1 RC9_REV 1 2 +1 1 RC9_TRIM 1500 4 +1 1 RCMAP_PITCH 2 2 +1 1 RCMAP_ROLL 1 2 +1 1 RCMAP_THROTTLE 3 2 +1 1 RCMAP_YAW 4 2 +1 1 RELAY_DEFAULT 0 2 +1 1 RELAY_PIN 54 2 +1 1 RELAY_PIN2 55 2 +1 1 RELAY_PIN3 -1 2 +1 1 RELAY_PIN4 -1 2 +1 1 RLL2SRV_D 0.019999999552965164 9 +1 1 RLL2SRV_FF 0.000000000000000000 9 +1 1 RLL2SRV_I 0.100000001490116119 9 +1 1 RLL2SRV_IMAX 3000 4 +1 1 RLL2SRV_P 0.600000023841857910 9 +1 1 RLL2SRV_RMAX 0 4 +1 1 RLL2SRV_TCONST 0.500000000000000000 9 +1 1 RNGFND2_ADDR 0 2 +1 1 RNGFND2_FUNCTION 0 2 +1 1 RNGFND2_GNDCLEAR 10 2 +1 1 RNGFND2_MAX_CM 700 4 +1 1 RNGFND2_MIN_CM 20 4 +1 1 RNGFND2_OFFSET 0.000000000000000000 9 +1 1 RNGFND2_PIN -1 2 +1 1 RNGFND2_RMETRIC 1 2 +1 1 RNGFND2_SCALING 3.000000000000000000 9 +1 1 RNGFND2_SETTLE 0 4 +1 1 RNGFND2_STOP_PIN -1 2 +1 1 RNGFND2_TYPE 0 2 +1 1 RNGFND_ADDR 0 2 +1 1 RNGFND_FUNCTION 0 2 +1 1 RNGFND_GNDCLEAR 10 2 +1 1 RNGFND_LANDING 0 2 +1 1 RNGFND_MAX_CM 700 4 +1 1 RNGFND_MIN_CM 20 4 +1 1 RNGFND_OFFSET 0.000000000000000000 9 +1 1 RNGFND_PIN -1 2 +1 1 RNGFND_PWRRNG 0 4 +1 1 RNGFND_RMETRIC 1 2 +1 1 RNGFND_SCALING 3.000000000000000000 9 +1 1 RNGFND_SETTLE 0 4 +1 1 RNGFND_STOP_PIN -1 2 +1 1 RNGFND_TYPE 0 2 +1 1 RPM2_SCALING 1.000000000000000000 9 +1 1 RPM2_TYPE 0 2 +1 1 RPM_MAX 100000.000000000000000000 9 +1 1 RPM_MIN 10.000000000000000000 9 +1 1 RPM_MIN_QUAL 0.500000000000000000 9 +1 1 RPM_SCALING 1.000000000000000000 9 +1 1 RPM_TYPE 0 2 +1 1 RSSI_ANA_PIN 0 2 +1 1 RSSI_CHANNEL 0 2 +1 1 RSSI_CHAN_HIGH 2000 4 +1 1 RSSI_CHAN_LOW 1000 4 +1 1 RSSI_PIN_HIGH 5.000000000000000000 9 +1 1 RSSI_PIN_LOW 0.000000000000000000 9 +1 1 RSSI_TYPE 0 2 +1 1 RST_MISSION_CH 0 2 +1 1 RST_SWITCH_CH 0 2 +1 1 RTL_AUTOLAND 0 2 +1 1 RTL_RADIUS 0 4 +1 1 RUDDER_ONLY 0 2 +1 1 SCALING_SPEED 15.000000000000000000 9 +1 1 SCHED_DEBUG 0 2 +1 1 SCHED_LOOP_RATE 50 4 +1 1 SERIAL0_BAUD 115 6 +1 1 SERIAL0_PROTOCOL 1 2 +1 1 SERIAL1_BAUD 57 6 +1 1 SERIAL1_PROTOCOL 1 2 +1 1 SERIAL2_BAUD 57 6 +1 1 SERIAL2_PROTOCOL 1 2 +1 1 SERIAL3_BAUD 38 6 +1 1 SERIAL3_PROTOCOL 5 2 +1 1 SERIAL4_BAUD 38 6 +1 1 SERIAL4_PROTOCOL 5 2 +1 1 SERIAL5_BAUD 57 6 +1 1 SERIAL5_PROTOCOL -1 2 +1 1 SR0_ADSB 5 4 +1 1 SR0_EXTRA1 10 4 +1 1 SR0_EXTRA2 10 4 +1 1 SR0_EXTRA3 3 4 +1 1 SR0_EXT_STAT 2 4 +1 1 SR0_PARAMS 10 4 +1 1 SR0_POSITION 3 4 +1 1 SR0_RAW_CTRL 1 4 +1 1 SR0_RAW_SENS 2 4 +1 1 SR0_RC_CHAN 2 4 +1 1 SR1_ADSB 5 4 +1 1 SR1_EXTRA1 1 4 +1 1 SR1_EXTRA2 1 4 +1 1 SR1_EXTRA3 1 4 +1 1 SR1_EXT_STAT 1 4 +1 1 SR1_PARAMS 10 4 +1 1 SR1_POSITION 1 4 +1 1 SR1_RAW_CTRL 1 4 +1 1 SR1_RAW_SENS 1 4 +1 1 SR1_RC_CHAN 1 4 +1 1 SR2_ADSB 5 4 +1 1 SR2_EXTRA1 1 4 +1 1 SR2_EXTRA2 1 4 +1 1 SR2_EXTRA3 1 4 +1 1 SR2_EXT_STAT 1 4 +1 1 SR2_PARAMS 10 4 +1 1 SR2_POSITION 1 4 +1 1 SR2_RAW_CTRL 1 4 +1 1 SR2_RAW_SENS 1 4 +1 1 SR2_RC_CHAN 1 4 +1 1 SR3_ADSB 5 4 +1 1 SR3_EXTRA1 1 4 +1 1 SR3_EXTRA2 1 4 +1 1 SR3_EXTRA3 1 4 +1 1 SR3_EXT_STAT 1 4 +1 1 SR3_PARAMS 10 4 +1 1 SR3_POSITION 1 4 +1 1 SR3_RAW_CTRL 1 4 +1 1 SR3_RAW_SENS 1 4 +1 1 SR3_RC_CHAN 1 4 +1 1 STAB_PITCH_DOWN 2.000000000000000000 9 +1 1 STALL_PREVENTION 1 2 +1 1 STEER2SRV_D 0.004999999888241291 9 +1 1 STEER2SRV_FF 0.000000000000000000 9 +1 1 STEER2SRV_I 0.200000002980232239 9 +1 1 STEER2SRV_IMAX 1500 4 +1 1 STEER2SRV_MINSPD 1.000000000000000000 9 +1 1 STEER2SRV_P 1.799999952316284180 9 +1 1 STEER2SRV_TCONST 0.750000000000000000 9 +1 1 STICK_MIXING 1 2 +1 1 SYSID_MYGCS 255 4 +1 1 SYSID_SW_TYPE 0 2 +1 1 SYSID_THISMAV 1 4 +1 1 SYS_NUM_RESETS 1 4 +1 1 TECS_APPR_SMAX 0.000000000000000000 9 +1 1 TECS_CLMB_MAX 5.000000000000000000 9 +1 1 TECS_HGT_OMEGA 3.000000000000000000 9 +1 1 TECS_INTEG_GAIN 0.100000001490116119 9 +1 1 TECS_LAND_ARSPD -1.000000000000000000 9 +1 1 TECS_LAND_DAMP 0.500000000000000000 9 +1 1 TECS_LAND_IGAIN 0.000000000000000000 9 +1 1 TECS_LAND_PDAMP 0.000000000000000000 9 +1 1 TECS_LAND_PMAX 10 2 +1 1 TECS_LAND_SINK 0.250000000000000000 9 +1 1 TECS_LAND_SPDWGT -1.000000000000000000 9 +1 1 TECS_LAND_SRC 0.000000000000000000 9 +1 1 TECS_LAND_TCONST 2.000000000000000000 9 +1 1 TECS_LAND_TDAMP 0.000000000000000000 9 +1 1 TECS_LAND_THR -1.000000000000000000 9 +1 1 TECS_PITCH_MAX 0 2 +1 1 TECS_PITCH_MIN 0 2 +1 1 TECS_PTCH_DAMP 0.000000000000000000 9 +1 1 TECS_RLL2THR 10.000000000000000000 9 +1 1 TECS_SINK_MAX 5.000000000000000000 9 +1 1 TECS_SINK_MIN 2.000000000000000000 9 +1 1 TECS_SPDWEIGHT 1.000000000000000000 9 +1 1 TECS_SPD_OMEGA 2.000000000000000000 9 +1 1 TECS_THR_DAMP 0.500000000000000000 9 +1 1 TECS_TIME_CONST 5.000000000000000000 9 +1 1 TECS_TKOFF_IGAIN 0.000000000000000000 9 +1 1 TECS_VERT_ACC 7.000000000000000000 9 +1 1 TELEM_DELAY 0 2 +1 1 TERRAIN_ENABLE 1 2 +1 1 TERRAIN_FOLLOW 0 2 +1 1 TERRAIN_LOOKAHD 2000 4 +1 1 TERRAIN_SPACING 100 4 +1 1 THROTTLE_NUDGE 1 2 +1 1 THR_FAILSAFE 1 2 +1 1 THR_FS_VALUE 950 4 +1 1 THR_MAX 75 2 +1 1 THR_MIN 0 2 +1 1 THR_PASS_STAB 0 2 +1 1 THR_SLEWRATE 100 2 +1 1 THR_SUPP_MAN 0 2 +1 1 TKOFF_FLAP_PCNT 0 2 +1 1 TKOFF_PLIM_SEC 2.000000000000000000 9 +1 1 TKOFF_ROTATE_SPD 0.000000000000000000 9 +1 1 TKOFF_TDRAG_ELEV 0 2 +1 1 TKOFF_TDRAG_SPD1 0.000000000000000000 9 +1 1 TKOFF_THR_DELAY 2 2 +1 1 TKOFF_THR_MAX 0 2 +1 1 TKOFF_THR_MINACC 0.000000000000000000 9 +1 1 TKOFF_THR_MINSPD 0.000000000000000000 9 +1 1 TKOFF_THR_SLEW 0 2 +1 1 TRIM_ARSPD_CM 1200 6 +1 1 TRIM_AUTO 0 2 +1 1 TRIM_PITCH_CD 0 4 +1 1 TRIM_RC_AT_START 0 2 +1 1 TRIM_THROTTLE 45 2 +1 1 TUNE_CHAN 0 2 +1 1 TUNE_CHAN_MAX 2000 4 +1 1 TUNE_CHAN_MIN 1000 4 +1 1 TUNE_ERR_THRESH 0.150000005960464478 9 +1 1 TUNE_MODE_REVERT 1 2 +1 1 TUNE_PARAM 0 4 +1 1 TUNE_RANGE 2.000000000000000000 9 +1 1 TUNE_SELECTOR 0 2 +1 1 USE_REV_THRUST 2 4 +1 1 VTAIL_OUTPUT 0 2 +1 1 WP_LOITER_RAD 60 4 +1 1 WP_MAX_RADIUS 0 4 +1 1 WP_RADIUS 90 4 +1 1 YAW2SRV_DAMP 0.000000000000000000 9 +1 1 YAW2SRV_IMAX 1500 4 +1 1 YAW2SRV_INT 0.000000000000000000 9 +1 1 YAW2SRV_RLL 1.000000000000000000 9 +1 1 YAW2SRV_SLIP 0.000000000000000000 9 diff --git a/src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml b/src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml index ce2a1e76a64ba8fe462e63ce86b789cb012730a9..88ed21e36f09b1908cc8e9ff77269a215dc3847c 100644 --- a/src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml +++ b/src/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml @@ -218,7 +218,7 @@ Column { anchors.left: parent.left anchors.right: parent.right flightMap: editorMap - polygon: root.polygon + polygon: geoFenceController.polygon sectionLabel: qsTr("Fence Polygon:") } } diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index 17ea75c40d5c082847dfe2eac87d5ff5147f12e1..3ee357f50928dff397a522d4d7eca8772778e5bc 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -216,6 +216,9 @@ public: /// Returns the parameter which holds the fence circle radius if supported. virtual QString geoFenceRadiusParam(Vehicle* vehicle) { Q_UNUSED(vehicle); return QString(); } + + /// Return the resource file which contains the set of params loaded for offline editing. + virtual QString offlineEditingParamFile(Vehicle* vehicle) { Q_UNUSED(vehicle); return QString(); } }; #endif diff --git a/src/FirmwarePlugin/GeoFenceEditor.qml b/src/FirmwarePlugin/GeoFenceEditor.qml index 7b5174a44793b456111935d355864a5de895c655..93138f1df88877333e7d04814ed86b8472bbb127 100644 --- a/src/FirmwarePlugin/GeoFenceEditor.qml +++ b/src/FirmwarePlugin/GeoFenceEditor.qml @@ -12,7 +12,7 @@ import QGroundControl.FactSystem 1.0 QGCLabel { width: availableWidth wrapMode: Text.WordWrap - text: qsTr("This vehicle does tno support GeoFence.") + text: qsTr("This vehicle does not support GeoFence.") //property var contoller - controller - Must be passed in from Loader //property real availableWidth - Available width for control - Must be passed in from Loader diff --git a/src/MissionManager/GeoFenceController.cc b/src/MissionManager/GeoFenceController.cc index 953f91102e757eb8684feb4add2ddd11ae8d11c4..1c3094c4702f88ffa960e9a7494739c6f72e2d6d 100644 --- a/src/MissionManager/GeoFenceController.cc +++ b/src/MissionManager/GeoFenceController.cc @@ -62,11 +62,11 @@ void GeoFenceController::_signalAll(void) emit editorQmlChanged(editorQml()); } -void GeoFenceController::_activeVehicleBeingRemoved(Vehicle* vehicle) +void GeoFenceController::_activeVehicleBeingRemoved(void) { _clearGeoFence(); _signalAll(); - vehicle->geoFenceManager()->disconnect(this); + _activeVehicle->geoFenceManager()->disconnect(this); } void GeoFenceController::_activeVehicleSet(void) @@ -122,23 +122,23 @@ void GeoFenceController::removeAll(void) void GeoFenceController::loadFromVehicle(void) { - if (_activeVehicle && _activeVehicle->getParameterLoader()->parametersAreReady() && !syncInProgress()) { + if (_activeVehicle->getParameterLoader()->parametersAreReady() && !syncInProgress()) { _activeVehicle->geoFenceManager()->loadFromVehicle(); } else { - qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle << _activeVehicle->getParameterLoader()->parametersAreReady() << syncInProgress(); + qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->getParameterLoader()->parametersAreReady() << syncInProgress(); } } void GeoFenceController::sendToVehicle(void) { - if (_activeVehicle && _activeVehicle->getParameterLoader()->parametersAreReady() && !syncInProgress()) { + if (_activeVehicle->getParameterLoader()->parametersAreReady() && !syncInProgress()) { _activeVehicle->geoFenceManager()->setPolygon(polygon()); _activeVehicle->geoFenceManager()->setBreachReturnPoint(breachReturnPoint()); setDirty(false); _polygon.setDirty(false); _activeVehicle->geoFenceManager()->sendToVehicle(); } else { - qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle << _activeVehicle->getParameterLoader()->parametersAreReady() << syncInProgress(); + qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->getParameterLoader()->parametersAreReady() << syncInProgress(); } } @@ -150,11 +150,7 @@ void GeoFenceController::_clearGeoFence(void) bool GeoFenceController::syncInProgress(void) const { - if (_activeVehicle) { - return _activeVehicle->geoFenceManager()->inProgress(); - } else { - return false; - } + return _activeVehicle->geoFenceManager()->inProgress(); } bool GeoFenceController::dirty(void) const @@ -183,38 +179,22 @@ void GeoFenceController::_polygonDirtyChanged(bool dirty) bool GeoFenceController::fenceSupported(void) const { - if (_activeVehicle) { - return _activeVehicle->geoFenceManager()->fenceSupported(); - } else { - return true; - } + return _activeVehicle->geoFenceManager()->fenceSupported(); } bool GeoFenceController::circleSupported(void) const { - if (_activeVehicle) { - return _activeVehicle->geoFenceManager()->circleSupported(); - } else { - return true; - } + return _activeVehicle->geoFenceManager()->circleSupported(); } bool GeoFenceController::polygonSupported(void) const { - if (_activeVehicle) { - return _activeVehicle->geoFenceManager()->polygonSupported(); - } else { - return true; - } + return _activeVehicle->geoFenceManager()->polygonSupported(); } bool GeoFenceController::breachReturnSupported(void) const { - if (_activeVehicle) { - return _activeVehicle->geoFenceManager()->breachReturnSupported(); - } else { - return true; - } + return _activeVehicle->geoFenceManager()->breachReturnSupported(); } void GeoFenceController::_setDirty(void) @@ -231,37 +211,20 @@ void GeoFenceController::_setPolygon(const QList& polygon) float GeoFenceController::circleRadius(void) const { - if (_activeVehicle) { - return _activeVehicle->geoFenceManager()->circleRadius(); - } else { - return 0.0; - } + return _activeVehicle->geoFenceManager()->circleRadius(); } QVariantList GeoFenceController::params(void) const { - if (_activeVehicle) { - return _activeVehicle->geoFenceManager()->params(); - } else { - return QVariantList(); - } + return _activeVehicle->geoFenceManager()->params(); } QStringList GeoFenceController::paramLabels(void) const { - if (_activeVehicle) { - return _activeVehicle->geoFenceManager()->paramLabels(); - } else { - return QStringList(); - } + return _activeVehicle->geoFenceManager()->paramLabels(); } QString GeoFenceController::editorQml(void) const { - if (_activeVehicle) { - return _activeVehicle->geoFenceManager()->editorQml(); - } else { - // FIXME: Offline editing support - return QString(); - } + return _activeVehicle->geoFenceManager()->editorQml(); } diff --git a/src/MissionManager/GeoFenceController.h b/src/MissionManager/GeoFenceController.h index d09895f28932ed2d2376a166a839a4a5631aa960..413c0cfdac33ce2e93bb2f37667b9280ac43046b 100644 --- a/src/MissionManager/GeoFenceController.h +++ b/src/MissionManager/GeoFenceController.h @@ -85,7 +85,7 @@ private: void _clearGeoFence(void); void _signalAll(void); - void _activeVehicleBeingRemoved(Vehicle* vehicle) final; + void _activeVehicleBeingRemoved(void) final; void _activeVehicleSet(void) final; bool _dirty; diff --git a/src/MissionManager/MissionCommandTreeTest.cc b/src/MissionManager/MissionCommandTreeTest.cc index 350f845d9258a783948f45b639a6908783ae309c..4f45b05ed43976c6f988f19e91d30fbbf9a8ac5e 100644 --- a/src/MissionManager/MissionCommandTreeTest.cc +++ b/src/MissionManager/MissionCommandTreeTest.cc @@ -174,12 +174,12 @@ void MissionCommandTreeTest::testJsonLoad(void) void MissionCommandTreeTest::testOverride(void) { // Generic/Generic should not have any overrides - Vehicle* vehicle = new Vehicle(MAV_AUTOPILOT_GENERIC, MAV_TYPE_GENERIC); + Vehicle* vehicle = new Vehicle(MAV_AUTOPILOT_GENERIC, MAV_TYPE_GENERIC, qgcApp()->toolbox()->firmwarePluginManager()); _checkBaseValues(_commandTree->getUIInfo(vehicle, (MAV_CMD)4), 4); delete vehicle; // Generic/FixedWing should have overrides - vehicle = new Vehicle(MAV_AUTOPILOT_GENERIC, MAV_TYPE_FIXED_WING); + vehicle = new Vehicle(MAV_AUTOPILOT_GENERIC, MAV_TYPE_FIXED_WING, qgcApp()->toolbox()->firmwarePluginManager()); _checkOverrideValues(_commandTree->getUIInfo(vehicle, (MAV_CMD)4), 4); delete vehicle; } @@ -195,7 +195,7 @@ void MissionCommandTreeTest::testAllTrees(void) // This will cause all of the variants of collapsed trees to be built foreach(MAV_AUTOPILOT firmwareType, firmwareList) { foreach (MAV_TYPE vehicleType, vehicleList) { - Vehicle* vehicle = new Vehicle(firmwareType, vehicleType); + Vehicle* vehicle = new Vehicle(firmwareType, vehicleType, qgcApp()->toolbox()->firmwarePluginManager()); qDebug() << firmwareType << vehicleType; QVERIFY(qgcApp()->toolbox()->missionCommandTree()->getUIInfo(vehicle, MAV_CMD_NAV_WAYPOINT) != NULL); delete vehicle; diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index d73604a97371174c40b8636118c12ef6f9537e0f..848ec8da56c092dc3fcac62485d9675d9b963fac 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -1023,17 +1023,17 @@ void MissionController::_itemCommandChanged(void) _recalcWaypointLines(); } -void MissionController::_activeVehicleBeingRemoved(Vehicle* vehicle) +void MissionController::_activeVehicleBeingRemoved(void) { - qCDebug(MissionControllerLog) << "_activeVehicleSet _activeVehicleBeingRemoved"; + qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved"; - MissionManager* missionManager = vehicle->missionManager(); + MissionManager* missionManager = _activeVehicle->missionManager(); disconnect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle); disconnect(missionManager, &MissionManager::inProgressChanged, this, &MissionController::_inProgressChanged); disconnect(missionManager, &MissionManager::currentItemChanged, this, &MissionController::_currentMissionItemChanged); - disconnect(vehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged); - disconnect(vehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged); + disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged); + disconnect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged); // We always remove all items on vehicle change. This leaves a user model hole: // If the user has unsaved changes in the Plan view they will lose them diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index a662c7e7804e9432f1cff5aaba6b66d4f1cb7dce..c82c74eeb212992c07e2a311dcdbbf7c685917ce 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -131,7 +131,7 @@ private: int _nextSequenceNumber(void); // Overrides from PlanElementController - void _activeVehicleBeingRemoved(Vehicle* vehicle) final; + void _activeVehicleBeingRemoved(void) final; void _activeVehicleSet(void) final; private: diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index 981b5e7769702fcd9bf24064649f8b9998779ba4..3131a28a9b7ef0d48747f065106c62ad394285c6 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -44,6 +44,10 @@ MissionManager::~MissionManager() void MissionManager::writeMissionItems(const QList& missionItems) { + if (_vehicle->isOfflineEditingVehicle()) { + return; + } + if (inProgress()) { qCDebug(MissionManagerLog) << "writeMissionItems called while transaction in progress"; return; @@ -131,6 +135,10 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC void MissionManager::requestMissionItems(void) { + if (_vehicle->isOfflineEditingVehicle()) { + return; + } + qCDebug(MissionManagerLog) << "requestMissionItems read sequence"; if (inProgress()) { diff --git a/src/MissionManager/PlanElementController.cc b/src/MissionManager/PlanElementController.cc index e8755903106ccf927e08f7c6387c5f8f1acc9732..c384d259e9999e6d0cad14a7f02acb608764e37c 100644 --- a/src/MissionManager/PlanElementController.cc +++ b/src/MissionManager/PlanElementController.cc @@ -9,11 +9,12 @@ #include "PlanElementController.h" #include "QGCApplication.h" +#include "MultiVehicleManager.h" PlanElementController::PlanElementController(QObject* parent) : QObject(parent) - , _activeVehicle(NULL) , _multiVehicleMgr(qgcApp()->toolbox()->multiVehicleManager()) + , _activeVehicle(_multiVehicleMgr->offlineEditingVehicle()) , _editMode(false) { @@ -34,16 +35,16 @@ void PlanElementController::start(bool editMode) void PlanElementController::_activeVehicleChanged(Vehicle* activeVehicle) { if (_activeVehicle) { - Vehicle* vehicleSave = _activeVehicle; + _activeVehicleBeingRemoved(); _activeVehicle = NULL; - _activeVehicleBeingRemoved(vehicleSave); } - _activeVehicle = activeVehicle; - - if (_activeVehicle) { - _activeVehicleSet(); + if (activeVehicle) { + _activeVehicle = activeVehicle; + } else { + _activeVehicle = _multiVehicleMgr->offlineEditingVehicle(); } + _activeVehicleSet(); // Whenever vehicle changes we need to update syncInProgress emit syncInProgressChanged(syncInProgress()); diff --git a/src/MissionManager/PlanElementController.h b/src/MissionManager/PlanElementController.h index 63b8ec73f0b463b4d0274474f1a42cb0794e1bf3..2ba0439358b0ed3cff0ea44270b7cf37d6de9ceb 100644 --- a/src/MissionManager/PlanElementController.h +++ b/src/MissionManager/PlanElementController.h @@ -52,13 +52,13 @@ signals: void dirtyChanged (bool dirty); protected: - Vehicle* _activeVehicle; MultiVehicleManager* _multiVehicleMgr; + Vehicle* _activeVehicle; ///< Currently active vehicle, can be disconnected offline editing vehicle bool _editMode; - /// Called when the current active vehicle has been removed. Derived classes should override - /// to implement custom behavior. When this is called _activeVehicle has already been cleared. - virtual void _activeVehicleBeingRemoved(Vehicle* removedVehicle) = 0; + /// Called when the current active vehicle is about to be removed. Derived classes should override + /// to implement custom behavior. + virtual void _activeVehicleBeingRemoved(void) = 0; /// Called when a new active vehicle has been set. Derived classes should override /// to implement custom behavior. diff --git a/src/MissionManager/SimpleMissionItemTest.cc b/src/MissionManager/SimpleMissionItemTest.cc index c7fccb22989b69f05ffe7509c80f5be5b35afd3e..097fbec3d302fd4b5784dd37a99d3d0603d924ff 100644 --- a/src/MissionManager/SimpleMissionItemTest.cc +++ b/src/MissionManager/SimpleMissionItemTest.cc @@ -10,6 +10,7 @@ #include "SimpleMissionItemTest.h" #include "SimpleMissionItem.h" +#include "QGCApplication.h" const SimpleMissionItemTest::ItemInfo_t SimpleMissionItemTest::_rgItemInfo[] = { { MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT }, @@ -80,7 +81,7 @@ SimpleMissionItemTest::SimpleMissionItemTest(void) void SimpleMissionItemTest::_testEditorFacts(void) { - Vehicle* vehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_FIXED_WING); + Vehicle* vehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_FIXED_WING, qgcApp()->toolbox()->firmwarePluginManager()); for (size_t i=0; i - #include "MultiVehicleManager.h" #include "AutoPilotPlugin.h" #include "MAVLinkProtocol.h" #include "UAS.h" #include "QGCApplication.h" #include "FollowMe.h" +#include "QGroundControlQmlGlobal.h" #ifdef __mobile__ #include "MobileScreenMgr.h" @@ -33,7 +30,7 @@ MultiVehicleManager::MultiVehicleManager(QGCApplication* app) , _activeVehicleAvailable(false) , _parameterReadyVehicleAvailable(false) , _activeVehicle(NULL) - , _disconnectedVehicle(NULL) + , _offlineEditingVehicle(NULL) , _firmwarePluginManager(NULL) , _autopilotPluginManager(NULL) , _joystickManager(NULL) @@ -50,8 +47,6 @@ MultiVehicleManager::MultiVehicleManager(QGCApplication* app) if (_gcsHeartbeatEnabled) { _gcsHeartbeatTimer.start(); } - - _disconnectedVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, this); } void MultiVehicleManager::setToolbox(QGCToolbox *toolbox) @@ -67,6 +62,11 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox) qmlRegisterUncreatableType("QGroundControl.MultiVehicleManager", 1, 0, "MultiVehicleManager", "Reference only"); connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo); + + _offlineEditingVehicle = new Vehicle(static_cast(QGroundControlQmlGlobal::offlineEditingFirmwareType()->rawValue().toInt()), + static_cast(QGroundControlQmlGlobal::offlineEditingVehicleType()->rawValue().toInt()), + _firmwarePluginManager, + this); } void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType) diff --git a/src/Vehicle/MultiVehicleManager.h b/src/Vehicle/MultiVehicleManager.h index fda1b4d17076bfc79ec76d76d0b777d1e72d6850..99695421c5f44f5841987f27a65d74b918e1e448 100644 --- a/src/Vehicle/MultiVehicleManager.h +++ b/src/Vehicle/MultiVehicleManager.h @@ -45,8 +45,8 @@ public: Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles CONSTANT) Q_PROPERTY(bool gcsHeartBeatEnabled READ gcsHeartbeatEnabled WRITE setGcsHeartbeatEnabled NOTIFY gcsHeartBeatEnabledChanged) - /// A disconnected vehicle is used to simulate vehicle information while no vehicle is connected. - Q_PROPERTY(Vehicle* disconnectedVehicle MEMBER _disconnectedVehicle CONSTANT) + /// A disconnected vehicle used for offline editing. It will match the vehicle type specified in Settings. + Q_PROPERTY(Vehicle* offlineEditingVehicle READ offlineEditingVehicle CONSTANT) // Methods @@ -68,6 +68,8 @@ public: bool gcsHeartbeatEnabled(void) const { return _gcsHeartbeatEnabled; } void setGcsHeartbeatEnabled(bool gcsHeartBeatEnabled); + Vehicle* offlineEditingVehicle(void) { return _offlineEditingVehicle; } + /// Determines if the link is in use by a Vehicle /// @param link Link to test against /// @param skipVehicle Don't consider this Vehicle as part of the test @@ -101,7 +103,7 @@ private: bool _activeVehicleAvailable; ///< true: An active vehicle is available bool _parameterReadyVehicleAvailable; ///< true: An active vehicle with ready parameters is available Vehicle* _activeVehicle; ///< Currently active vehicle from a ui perspective - Vehicle* _disconnectedVehicle; ///< Disconnected vechicle for FactGroup access + Vehicle* _offlineEditingVehicle; ///< Disconnected vechicle used for offline editing QList _vehiclesBeingDeleted; ///< List of Vehicles being deleted in queued phases Vehicle* _vehicleBeingSetActive; ///< Vehicle being set active in queued phases diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 0be53140c60d0a64d8237185854f8184c0bb75b6..7a4b4586a74a5299f9ee9c65cce683e4fce4bf4a 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -65,7 +65,7 @@ Vehicle::Vehicle(LinkInterface* link, : FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json") , _id(vehicleId) , _active(false) - , _disconnectedVehicle(false) + , _offlineEditingVehicle(false) , _firmwareType(firmwareType) , _vehicleType(vehicleType) , _firmwarePlugin(NULL) @@ -203,7 +203,7 @@ Vehicle::Vehicle(LinkInterface* link, connect(_parameterLoader, &ParameterLoader::parametersReady, _autopilotPlugin, &AutoPilotPlugin::_parametersReadyPreChecks); connect(_parameterLoader, &ParameterLoader::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress); - // GeoFenceManager needs to access ParameterLoader so make sure to create afters + // GeoFenceManager needs to access ParameterLoader so make sure to create after _geoFenceManager = _firmwarePlugin->newGeoFenceManager(this); connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError); @@ -254,12 +254,15 @@ Vehicle::Vehicle(LinkInterface* link, _vibrationFactGroup.setVehicle(this); } -// Disconnected Vehicle -Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, QObject* parent) +// Disconnected Vehicle for offline editing +Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, + MAV_TYPE vehicleType, + FirmwarePluginManager* firmwarePluginManager, + QObject* parent) : FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json", parent) , _id(0) , _active(false) - , _disconnectedVehicle(true) + , _offlineEditingVehicle(true) , _firmwareType(firmwareType) , _vehicleType(vehicleType) , _firmwarePlugin(NULL) @@ -290,12 +293,14 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, QObject* pare , _connectionLostEnabled(true) , _missionManager(NULL) , _missionManagerInitialRequestComplete(false) + , _geoFenceManager(NULL) + , _geoFenceManagerInitialRequestComplete(false) , _parameterLoader(NULL) , _armed(false) , _base_mode(0) , _custom_mode(0) , _nextSendMessageMultipleIndex(0) - , _firmwarePluginManager(NULL) + , _firmwarePluginManager(firmwarePluginManager) , _autopilotPluginManager(NULL) , _joystickManager(NULL) , _flowImageIndex(0) @@ -322,10 +327,16 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, QObject* pare , _windFactGroup(this) , _vibrationFactGroup(this) { - // This is a hack for disconnected vehicle used while unit testing - if (qgcApp()->toolbox() && qgcApp()->toolbox()->firmwarePluginManager()) { - _firmwarePlugin = qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(_firmwareType, _vehicleType); - } + _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType); + + _missionManager = new MissionManager(this); + connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); + + _parameterLoader = new ParameterLoader(this); + + // GeoFenceManager needs to access ParameterLoader so make sure to create after + _geoFenceManager = _firmwarePlugin->newGeoFenceManager(this); + connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError); // Build FactGroup object model @@ -1406,11 +1417,6 @@ void Vehicle::disconnectInactiveVehicle(void) } } -ParameterLoader* Vehicle::getParameterLoader(void) -{ - return _parameterLoader; -} - void Vehicle::_imageReady(UASInterface*) { if(_uas) @@ -1829,7 +1835,7 @@ void Vehicle::motorTest(int motor, int percent, int timeoutSecs) /// Returns true if the specifed parameter exists from the default component bool Vehicle::parameterExists(int componentId, const QString& name) const { - return _autopilotPlugin->parameterExists(componentId, name); + return getParameterLoader()->parameterExists(componentId, name); } /// Returns the specified parameter Fact from the default component @@ -1837,7 +1843,7 @@ bool Vehicle::parameterExists(int componentId, const QString& name) const /// parameterExists. Fact* Vehicle::getParameterFact(int componentId, const QString& name) { - return _autopilotPlugin->getParameterFact(componentId, name); + return getParameterLoader()->getFact(componentId, name); } void Vehicle::_newMissionItemsAvailable(void) diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 2a6def0d5fd9d084df2800bd249ac857f84b6577..86946a4451a4a533fc28995cbd9cc1062f35c36f 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -216,9 +216,11 @@ public: AutoPilotPluginManager* autopilotPluginManager, JoystickManager* joystickManager); - // The following is used to create a disconnected Vehicle. Disconnected vehicles are used used to access FactGroup information - // without needing a real connection as well as offline mission planning. - Vehicle(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, QObject* parent = NULL); + // The following is used to create a disconnected Vehicle for use while offline editing. + Vehicle(MAV_AUTOPILOT firmwareType, + MAV_TYPE vehicleType, + FirmwarePluginManager* firmwarePluginManager, + QObject* parent = NULL); ~Vehicle(); @@ -276,6 +278,7 @@ public: Q_PROPERTY(int motorCount READ motorCount CONSTANT) Q_PROPERTY(bool coaxialMotors READ coaxialMotors CONSTANT) Q_PROPERTY(bool xConfigMotors READ xConfigMotors CONSTANT) + Q_PROPERTY(bool isOfflineEditingVehicle READ isOfflineEditingVehicle CONSTANT) /// true: Vehicle is flying, false: Vehicle is on ground Q_PROPERTY(bool flying READ flying WRITE setFlying NOTIFY flyingChanged) @@ -497,32 +500,33 @@ public: MessageError } MessageType_t; - bool messageTypeNone () { return _currentMessageType == MessageNone; } - bool messageTypeNormal () { return _currentMessageType == MessageNormal; } - bool messageTypeWarning () { return _currentMessageType == MessageWarning; } - bool messageTypeError () { return _currentMessageType == MessageError; } - int newMessageCount () { return _currentMessageCount; } - int messageCount () { return _messageCount; } - QString formatedMessages (); - QString formatedMessage () { return _formatedMessage; } - QString latestError () { return _latestError; } - float latitude () { return _coordinate.latitude(); } - float longitude () { return _coordinate.longitude(); } - bool mavPresent () { return _mav != NULL; } - QString currentState () { return _currentState; } - int rcRSSI () { return _rcRSSI; } - bool px4Firmware () const { return _firmwareType == MAV_AUTOPILOT_PX4; } - bool apmFirmware () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; } - bool genericFirmware () const { return !px4Firmware() && !apmFirmware(); } - bool connectionLost () const { return _connectionLost; } - bool connectionLostEnabled() const { return _connectionLostEnabled; } - uint messagesReceived () { return _messagesReceived; } - uint messagesSent () { return _messagesSent; } - uint messagesLost () { return _messagesLost; } - bool flying () const { return _flying; } - bool guidedMode () const; - uint8_t baseMode () const { return _base_mode; } - uint32_t customMode () const { return _custom_mode; } + bool messageTypeNone () { return _currentMessageType == MessageNone; } + bool messageTypeNormal () { return _currentMessageType == MessageNormal; } + bool messageTypeWarning () { return _currentMessageType == MessageWarning; } + bool messageTypeError () { return _currentMessageType == MessageError; } + int newMessageCount () { return _currentMessageCount; } + int messageCount () { return _messageCount; } + QString formatedMessages (); + QString formatedMessage () { return _formatedMessage; } + QString latestError () { return _latestError; } + float latitude () { return _coordinate.latitude(); } + float longitude () { return _coordinate.longitude(); } + bool mavPresent () { return _mav != NULL; } + QString currentState () { return _currentState; } + int rcRSSI () { return _rcRSSI; } + bool px4Firmware () const { return _firmwareType == MAV_AUTOPILOT_PX4; } + bool apmFirmware () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; } + bool genericFirmware () const { return !px4Firmware() && !apmFirmware(); } + bool connectionLost () const { return _connectionLost; } + bool connectionLostEnabled () const { return _connectionLostEnabled; } + uint messagesReceived () { return _messagesReceived; } + uint messagesSent () { return _messagesSent; } + uint messagesLost () { return _messagesLost; } + bool flying () const { return _flying; } + bool guidedMode () const; + uint8_t baseMode () const { return _base_mode; } + uint32_t customMode () const { return _custom_mode; } + bool isOfflineEditingVehicle () const { return _offlineEditingVehicle; } Fact* roll (void) { return &_rollFact; } Fact* heading (void) { return &_headingFact; } @@ -540,7 +544,8 @@ public: void setConnectionLostEnabled(bool connectionLostEnabled); - ParameterLoader* getParameterLoader(void); + ParameterLoader* getParameterLoader(void) { return _parameterLoader; } + ParameterLoader* getParameterLoader(void) const { return _parameterLoader; } static const int cMaxRcChannels = 18; @@ -697,9 +702,9 @@ private: QString _vehicleIdSpeech(void); private: - int _id; ///< Mavlink system id + int _id; ///< Mavlink system id bool _active; - bool _disconnectedVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use when no active vehicle is available + bool _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing MAV_AUTOPILOT _firmwareType; MAV_TYPE _vehicleType; diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index 7d16a0ff08847df34c7ab20c6d25e9f1533af4f3..e04ce20e75eb53a490caa647b02f595e18910481 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -125,7 +125,7 @@ QGCView { anchors.horizontalCenter: parent.horizontalCenter QGCLabel { id: offlineLabel - text: qsTr("Offline Mission Editing") + text: qsTr("Offline Mission Editing (Requires Restart)") font.family: ScreenTools.demiboldFontFamily } }