Commit 80a1f005 authored by DonLakeFlyer's avatar DonLakeFlyer

Update for 4.0 releases

parent 4ef7a813
......@@ -428,7 +428,7 @@ SetupPage {
FactTextField {
id: tuneMinField
validator: DoubleValidator {bottom: 0; top: 32767;}
fact: controller.getParameterFact(-1, "TUNE_LOW")
fact: controller.getParameterFact(-1, "r.TUNE_MAX")
}
QGCLabel {
......@@ -440,7 +440,7 @@ SetupPage {
FactTextField {
id: tuneMaxField
validator: DoubleValidator {bottom: 0; top: 32767;}
fact: controller.getParameterFact(-1, "TUNE_HIGH")
fact: controller.getParameterFact(-1, "r.TUNE_MIN")
}
}
} // Column - Channel 6 Tuning option
......
......@@ -829,10 +829,13 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case MAV_TYPE_TRICOPTER:
case MAV_TYPE_COAXIAL:
case MAV_TYPE_HELICOPTER:
if (vehicle->versionCompare(3, 7, 0) >= 0) { // 3.7.0 and higher
if (vehicle->versionCompare(4, 0, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.4.0.xml");
}
if (vehicle->versionCompare(3, 7, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml");
}
if (vehicle->versionCompare(3, 6, 0) >= 0) { // 3.6.0 and higher
if (vehicle->versionCompare(3, 6, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml");
}
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml");
......@@ -845,6 +848,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
case MAV_TYPE_FIXED_WING:
if (vehicle->versionCompare(4, 0, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.4.0.xml");
}
if (vehicle->versionCompare(3, 10, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.10.xml");
}
......@@ -855,6 +861,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case MAV_TYPE_GROUND_ROVER:
case MAV_TYPE_SURFACE_BOAT:
if (vehicle->versionCompare(4, 0, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.4.0.xml");
}
if (vehicle->versionCompare(3, 6, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.6.xml");
}
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
......@@ -45,12 +45,15 @@
<file alias="APMParameterFactMetaData.Plane.3.8.xml">APMParameterFactMetaData.Plane.3.8.xml</file>
<file alias="APMParameterFactMetaData.Plane.3.9.xml">APMParameterFactMetaData.Plane.3.9.xml</file>
<file alias="APMParameterFactMetaData.Plane.3.10.xml">APMParameterFactMetaData.Plane.3.10.xml</file>
<file alias="APMParameterFactMetaData.Plane.4.0.xml">APMParameterFactMetaData.Plane.4.0.xml</file>
<file alias="APMParameterFactMetaData.Copter.3.5.xml">APMParameterFactMetaData.Copter.3.5.xml</file>
<file alias="APMParameterFactMetaData.Copter.3.6.xml">APMParameterFactMetaData.Copter.3.6.xml</file>
<file alias="APMParameterFactMetaData.Copter.3.7.xml">APMParameterFactMetaData.Copter.3.7.xml</file>
<file alias="APMParameterFactMetaData.Copter.4.0.xml">APMParameterFactMetaData.Copter.4.0.xml</file>
<file alias="APMParameterFactMetaData.Rover.3.4.xml">APMParameterFactMetaData.Rover.3.4.xml</file>
<file alias="APMParameterFactMetaData.Rover.3.5.xml">APMParameterFactMetaData.Rover.3.5.xml</file>
<file alias="APMParameterFactMetaData.Rover.3.6.xml">APMParameterFactMetaData.Rover.3.6.xml</file>
<file alias="APMParameterFactMetaData.Rover.4.0.xml">APMParameterFactMetaData.Rover.4.0.xml</file>
<file alias="APMParameterFactMetaData.Sub.3.4.xml">APMParameterFactMetaData.Sub.3.4.xml</file>
<file alias="APMParameterFactMetaData.Sub.3.5.xml">APMParameterFactMetaData.Sub.3.5.xml</file>
<file alias="APMParameterFactMetaData.Sub.3.6dev.xml">APMParameterFactMetaData.Sub.3.6dev.xml</file>
......
......@@ -97,6 +97,11 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
remapV3_7["RC11_OPTION"] = QStringLiteral("CH11_OPT");
remapV3_7["RC12_OPTION"] = QStringLiteral("CH12_OPT");
FirmwarePlugin::remapParamNameMap_t& remapV4_0 = _remapParamName[4][0];
remapV4_0["TUNE_MIN"] = QStringLiteral("TUNE_HIGH");
remapV3_7["TUNE_MAX"] = QStringLiteral("TUNE_LOW");
_remapParamNameIntialized = true;
}
}
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment