Browse Source

Merge pull request #7330 from DonLakeFlyer/master

ArduCopter 3.7 CH#_OPT -> RC#_OPTION name change
QGC4.4
Don Gagne 6 years ago committed by GitHub
parent
commit
1d8d52c101
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 1
      ChangeLog.md
  2. 5
      src/AutoPilotPlugins/APM/APMTuningComponent.cc
  3. 22
      src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml
  4. 3
      src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
  5. 14791
      src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml
  6. 1
      src/FirmwarePlugin/APM/APMResources.qrc
  7. 6
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
  8. 6
      src/FirmwarePlugin/APM/BuildParamMetaData.sh

1
ChangeLog.md

@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes. @@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build
* ArduCopter: Handle 3.7 parameter name change from CH#_OPT to RC#_OPTION.
* Improved support for flashing/connecting to ChibiOS bootloaders boards.
* Making the camera API available to all firmwares, not just PX4.
* ArduPilot: Support configurable mavlink stream rates. Available from Settings/Mavlink page.

5
src/AutoPilotPlugins/APM/APMTuningComponent.cc

@ -60,10 +60,7 @@ QUrl APMTuningComponent::setupSource(void) const @@ -60,10 +60,7 @@ QUrl APMTuningComponent::setupSource(void) const
case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
// Older firmwares do not have CH9_OPT, we don't support Tuning on older firmwares
if (_vehicle->parameterManager()->parameterExists(-1, QStringLiteral("CH9_OPT"))) {
qmlFile = QStringLiteral("qrc:/qml/APMTuningComponentCopter.qml");
}
qmlFile = QStringLiteral("qrc:/qml/APMTuningComponentCopter.qml");
break;
case MAV_TYPE_SUBMARINE:
qmlFile = QStringLiteral("qrc:/qml/APMTuningComponentSub.qml");

22
src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml

@ -43,12 +43,12 @@ SetupPage { @@ -43,12 +43,12 @@ SetupPage {
property Fact _rateClimbP: controller.getParameterFact(-1, "r.PSC_ACCZ_P")
property Fact _rateClimbI: controller.getParameterFact(-1, "r.PSC_ACCZ_I")
property Fact _ch7Opt: controller.getParameterFact(-1, "CH7_OPT")
property Fact _ch8Opt: controller.getParameterFact(-1, "CH8_OPT")
property Fact _ch9Opt: controller.getParameterFact(-1, "CH9_OPT")
property Fact _ch10Opt: controller.getParameterFact(-1, "CH10_OPT")
property Fact _ch11Opt: controller.getParameterFact(-1, "CH11_OPT")
property Fact _ch12Opt: controller.getParameterFact(-1, "CH12_OPT")
property Fact _ch7Opt: controller.getParameterFact(-1, "r.RC7_OPTION")
property Fact _ch8Opt: controller.getParameterFact(-1, "r.RC8_OPTION")
property Fact _ch9Opt: controller.getParameterFact(-1, "r.RC9_OPTION")
property Fact _ch10Opt: controller.getParameterFact(-1, "r.RC10_OPTION")
property Fact _ch11Opt: controller.getParameterFact(-1, "r.RC11_OPTION")
property Fact _ch12Opt: controller.getParameterFact(-1, "r.RC12_OPTION")
readonly property int _firstOptionChannel: 7
readonly property int _lastOptionChannel: 12
@ -84,12 +84,12 @@ SetupPage { @@ -84,12 +84,12 @@ SetupPage {
calcAutoTuneChannel()
}
/// The AutoTune switch is stored in one of the CH#_OPT parameters. We need to loop through those
/// The AutoTune switch is stored in one of the RC#_OPTION parameters. We need to loop through those
/// to find them and setup the ui accordindly.
function calcAutoTuneChannel() {
_autoTuneSwitchChannelIndex = 0
for (var channel=_firstOptionChannel; channel<=_lastOptionChannel; channel++) {
var optionFact = controller.getParameterFact(-1, "CH" + channel + "_OPT")
var optionFact = controller.getParameterFact(-1, "r.RC" + channel + "_OPTION")
if (optionFact.value == _autoTuneOption) {
_autoTuneSwitchChannelIndex = channel - _firstOptionChannel + 1
break
@ -101,7 +101,7 @@ SetupPage { @@ -101,7 +101,7 @@ SetupPage {
function setChannelAutoTuneOption(channel) {
// First clear any previous settings for AutTune
for (var optionChannel=_firstOptionChannel; optionChannel<=_lastOptionChannel; optionChannel++) {
var optionFact = controller.getParameterFact(-1, "CH" + optionChannel + "_OPT")
var optionFact = controller.getParameterFact(-1, "r.RC" + optionChannel + "_OPTION")
if (optionFact.value == _autoTuneOption) {
optionFact.value = 0
}
@ -109,7 +109,7 @@ SetupPage { @@ -109,7 +109,7 @@ SetupPage {
// Now set the function into the new channel
if (channel != 0) {
var optionFact = controller.getParameterFact(-1, "CH" + channel + "_OPT")
var optionFact = controller.getParameterFact(-1, "r.RC" + channel + "_OPTION")
optionFact.value = _autoTuneOption
}
}
@ -368,7 +368,7 @@ SetupPage { @@ -368,7 +368,7 @@ SetupPage {
QGCLabel {
anchors.baseline: optCombo.baseline
text: qsTr("Channel Option 6 (Tuning):")
text: qsTr("RC Channel 6 Option (Tuning):")
//color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text
}

3
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

@ -807,6 +807,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) @@ -807,6 +807,9 @@ 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
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml");
}
if (vehicle->versionCompare(3, 6, 0) >= 0) { // 3.6.0 and higher
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml");
}

14791
src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml

File diff suppressed because it is too large Load Diff

1
src/FirmwarePlugin/APM/APMResources.qrc

@ -49,6 +49,7 @@ @@ -49,6 +49,7 @@
<file alias="APMParameterFactMetaData.Copter.3.4.xml">APMParameterFactMetaData.Copter.3.4.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.Rover.3.0.xml">APMParameterFactMetaData.Rover.3.0.xml</file>
<file alias="APMParameterFactMetaData.Rover.3.2.xml">APMParameterFactMetaData.Rover.3.2.xml</file>
<file alias="APMParameterFactMetaData.Rover.3.4.xml">APMParameterFactMetaData.Rover.3.4.xml</file>

6
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc

@ -162,6 +162,12 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void) @@ -162,6 +162,12 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
remapV3_7["BATT_ARM_VOLT"] = QStringLiteral("ARMING_VOLT_MIN");
remapV3_7["BATT2_ARM_VOLT"] = QStringLiteral("ARMING_VOLT2_MIN");
remapV3_7["RC7_OPTION"] = QStringLiteral("CH7_OPT");
remapV3_7["RC8_OPTION"] = QStringLiteral("CH8_OPT");
remapV3_7["RC9_OPTION"] = QStringLiteral("CH9_OPT");
remapV3_7["RC10_OPTION"] = QStringLiteral("CH10_OPT");
remapV3_7["RC11_OPTION"] = QStringLiteral("CH11_OPT");
remapV3_7["RC12_OPTION"] = QStringLiteral("CH12_OPT");
_remapParamNameIntialized = true;
}

6
src/FirmwarePlugin/APM/BuildParamMetaData.sh

@ -0,0 +1,6 @@ @@ -0,0 +1,6 @@
cd ~/repos/ardupilot
rm apm.pdef.xml
./Tools/autotest/param_metadata/param_parse.py --vehicle ArduCopter
cp apm.pdef.xml ~/repos/qgroundcontrol/src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml
rm apm.pdef.xml
cd ~/repos/qgroundcontrol/src/FirmwarePlugin/APM
Loading…
Cancel
Save