diff --git a/ChangeLog.md b/ChangeLog.md index e83bdc255c27619f498facea1f64d3dbee0798f9..752ca7aa6baae015db0ccb541868c7fcd8e8f925 100644 --- a/ChangeLog.md +++ b/ChangeLog.md @@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes. ### 3.6.0 - Daily Build +* ArduCopter: Add PID Tuning page to Tuning Setup * ArduPilot: Copter - Advanced Tuning support * ArduPilot: Rover - Frame setup support * ArduPilot: Copter - Update support to 3.5+ diff --git a/src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml b/src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml index 77395d00e8a887db7ce24aecdd589ed285d41fa1..9efd5efdf5dac5a83058a0f0e9be49e98b693c52 100644 --- a/src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml +++ b/src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml @@ -26,16 +26,13 @@ SetupPage { id: tuningPageComponent Column { - width: availableWidth - spacing: _margins + width: availableWidth FactPanelController { id: controller; factPanel: tuningPage.viewPanel } QGCPalette { id: palette; colorGroupEnabled: true } - property bool _rcFeelAvailable: controller.parameterExists(-1, "RC_FEEL") property bool _atcInputTCAvailable: controller.parameterExists(-1, "ATC_INPUT_TC") - property Fact _rcFeel: controller.getParameterFact(-1, "RC_FEEL", false) property Fact _atcInputTC: controller.getParameterFact(-1, "ATC_INPUT_TC", false) property Fact _rateRollP: controller.getParameterFact(-1, "ATC_RAT_RLL_P") property Fact _rateRollI: controller.getParameterFact(-1, "ATC_RAT_RLL_I") @@ -69,6 +66,7 @@ SetupPage { ExclusiveGroup { id: returnAltRadioGroup } Component.onCompleted: { + showAdvanced = !ScreenTools.isMobile // Qml Sliders have a strange behavior in which they first set Slider::value to some internal // setting and then set Slider::value to the bound properties value. If you have an onValueChanged // handler which updates your property with the new value, this first value change will trash @@ -76,9 +74,6 @@ SetupPage { // after Qml load is done. We also don't track value changes until Qml load completes. rollPitch.value = _rateRollP.value climb.value = _rateClimbP.value - if (_rcFeelAvailable) { - rcFeel.value = _rcFeel.value - } if (_atcInputTCAvailable) { atcInputTC.value = _atcInputTC.value } @@ -124,382 +119,365 @@ SetupPage { Connections { target: _ch11Opt; onValueChanged: calcAutoTuneChannel() } Connections { target: _ch12Opt; onValueChanged: calcAutoTuneChannel() } - QGCLabel { - text: qsTr("Basic Tuning") - font.family: ScreenTools.demiboldFontFamily - } - - Rectangle { - id: basicTuningRect + Column { anchors.left: parent.left anchors.right: parent.right - height: basicTuningColumn.y + basicTuningColumn.height + _margins - color: palette.windowShade + spacing: _margins + visible: !advanced + + QGCLabel { + text: qsTr("Basic Tuning") + font.family: ScreenTools.demiboldFontFamily + } - Column { - id: basicTuningColumn - anchors.margins: _margins + Rectangle { + id: basicTuningRect anchors.left: parent.left anchors.right: parent.right - anchors.top: parent.top - spacing: _margins + height: basicTuningColumn.y + basicTuningColumn.height + _margins + color: palette.windowShade Column { - anchors.left: parent.left - anchors.right: parent.right - - QGCLabel { - text: qsTr("Roll/Pitch Sensitivity") - font.family: ScreenTools.demiboldFontFamily - } + id: basicTuningColumn + anchors.margins: _margins + anchors.left: parent.left + anchors.right: parent.right + anchors.top: parent.top + spacing: _margins - QGCLabel { - text: qsTr("Slide to the right if the copter is sluggish or slide to the left if the copter is twitchy") - } - - Slider { - id: rollPitch + Column { anchors.left: parent.left anchors.right: parent.right - minimumValue: 0.08 - maximumValue: 0.4 - stepSize: 0.01 - tickmarksEnabled: true - - onValueChanged: { - if (_loadComplete) { - _rateRollP.value = value - _rateRollI.value = value - _ratePitchP.value = value - _ratePitchI.value = value - } - } - } - } - Column { - anchors.left: parent.left - anchors.right: parent.right - - QGCLabel { - text: qsTr("Climb Sensitivity") - font.family: ScreenTools.demiboldFontFamily - } + QGCLabel { + text: qsTr("Roll/Pitch Sensitivity") + font.family: ScreenTools.demiboldFontFamily + } - QGCLabel { - text: qsTr("Slide to the right to climb more aggressively or slide to the left to climb more gently") - } + QGCLabel { + text: qsTr("Slide to the right if the copter is sluggish or slide to the left if the copter is twitchy") + } - Slider { - id: climb - anchors.left: parent.left - anchors.right: parent.right - minimumValue: 0.3 - maximumValue: 1.0 - stepSize: 0.02 - tickmarksEnabled: true - value: _rateClimbP.value - - onValueChanged: { - if (_loadComplete) { - _rateClimbP.value = value - _rateClimbI.value = value * 2 + Slider { + id: rollPitch + anchors.left: parent.left + anchors.right: parent.right + minimumValue: 0.08 + maximumValue: 0.4 + stepSize: 0.01 + tickmarksEnabled: true + + onValueChanged: { + if (_loadComplete) { + _rateRollP.value = value + _rateRollI.value = value + _ratePitchP.value = value + _ratePitchI.value = value + } } } } - } - Column { - anchors.left: parent.left - anchors.right: parent.right - visible: _rcFeelAvailable + Column { + anchors.left: parent.left + anchors.right: parent.right - QGCLabel { - text: qsTr("RC Roll/Pitch Feel") - font.family: ScreenTools.demiboldFontFamily - } + QGCLabel { + text: qsTr("Climb Sensitivity") + font.family: ScreenTools.demiboldFontFamily + } - QGCLabel { - text: qsTr("Slide to the left for soft control, slide to the right for crisp control") - } + QGCLabel { + text: qsTr("Slide to the right to climb more aggressively or slide to the left to climb more gently") + } - Slider { - id: rcFeel - anchors.left: parent.left - anchors.right: parent.right - minimumValue: 0 - maximumValue: 100 - stepSize: 5.0 - tickmarksEnabled: true - - onValueChanged: { - if (_loadComplete) { - _rcFeel.value = value + Slider { + id: climb + anchors.left: parent.left + anchors.right: parent.right + minimumValue: 0.3 + maximumValue: 1.0 + stepSize: 0.02 + tickmarksEnabled: true + value: _rateClimbP.value + + onValueChanged: { + if (_loadComplete) { + _rateClimbP.value = value + _rateClimbI.value = value * 2 + } } } } - } - Column { - anchors.left: parent.left - anchors.right: parent.right - visible: _atcInputTCAvailable + Column { + anchors.left: parent.left + anchors.right: parent.right + visible: _atcInputTCAvailable - QGCLabel { - text: qsTr("RC Roll/Pitch Feel") - font.family: ScreenTools.demiboldFontFamily - } + QGCLabel { + text: qsTr("RC Roll/Pitch Feel") + font.family: ScreenTools.demiboldFontFamily + } - QGCLabel { - text: qsTr("Slide to the left for soft control, slide to the right for crisp control") - } + QGCLabel { + text: qsTr("Slide to the left for soft control, slide to the right for crisp control") + } - Slider { - id: atcInputTC - anchors.left: parent.left - anchors.right: parent.right - minimumValue: _atcInputTC.min - maximumValue: _atcInputTC.max - stepSize: _atcInputTC.increment - tickmarksEnabled: true - - onValueChanged: { - if (_loadComplete) { - _atcInputTC.value = value + Slider { + id: atcInputTC + anchors.left: parent.left + anchors.right: parent.right + minimumValue: _atcInputTC.min + maximumValue: _atcInputTC.max + stepSize: _atcInputTC.increment + tickmarksEnabled: true + + onValueChanged: { + if (_loadComplete) { + _atcInputTC.value = value + } } } } - } - } - } // Rectangle - Basic tuning - - QGCLabel { - text: qsTr("Advanced Tuning") - font.family: ScreenTools.demiboldFontFamily - } - Rectangle { - anchors.left: parent.left - anchors.right: parent.right - height: advColumnLayout.y + advColumnLayout.height + _margins - color: palette.windowShade - - ColumnLayout { - id: advColumnLayout - anchors.margins: _margins - anchors.left: parent.left - anchors.right: parent.right - anchors.top: parent.top - spacing: _margins - - Column { - Layout.fillWidth: true + Column { + anchors.left: parent.left + anchors.right: parent.right - QGCLabel { - text: qsTr("Spin While Armed") - font.family: ScreenTools.demiboldFontFamily - } + QGCLabel { + text: qsTr("Spin While Armed") + font.family: ScreenTools.demiboldFontFamily + } - QGCLabel { - text: qsTr("Adjust the amount the motors spin to indicate armed") - } + QGCLabel { + text: qsTr("Adjust the amount the motors spin to indicate armed") + } - Slider { - anchors.left: parent.left - anchors.right: parent.right - minimumValue: 0 - maximumValue: Math.max(0.3, _motSpinArm.rawValue) - stepSize: 0.01 - tickmarksEnabled: true - value: _motSpinArm.rawValue - - onValueChanged: { - if (_loadComplete) { - _motSpinArm.rawValue = value + Slider { + anchors.left: parent.left + anchors.right: parent.right + minimumValue: 0 + maximumValue: Math.max(0.3, _motSpinArm.rawValue) + stepSize: 0.01 + tickmarksEnabled: true + value: _motSpinArm.rawValue + + onValueChanged: { + if (_loadComplete) { + _motSpinArm.rawValue = value + } } } } - } - Column { - id: lastAdvTuningColumn - Layout.fillWidth: true + Column { + anchors.left: parent.left + anchors.right: parent.right - QGCLabel { - text: qsTr("Minimum Thrust") - font.family: ScreenTools.demiboldFontFamily - } + QGCLabel { + text: qsTr("Minimum Thrust") + font.family: ScreenTools.demiboldFontFamily + } - QGCLabel { - text: qsTr("Adjust the minimum amount of thrust for a stable minimum throttle descent") - } + QGCLabel { + text: qsTr("Adjust the minimum amount of thrust require for the vehicle to move") + } - QGCLabel { - text: qsTr("Warning: This setting should be higher than 'Spin While Armed'") - color: palette.warningText - visible: _motSpinMin.rawValue < _motSpinArm.rawValue - } + QGCLabel { + text: qsTr("Warning: This setting should be higher than 'Spin While Armed'") + color: palette.warningText + visible: _motSpinMin.rawValue < _motSpinArm.rawValue + } - Slider { - anchors.left: parent.left - anchors.right: parent.right - minimumValue: 0 - maximumValue: Math.max(0.3, _motSpinMin.rawValue) - stepSize: 0.01 - tickmarksEnabled: true - value: _motSpinMin.rawValue - - onValueChanged: { - if (_loadComplete) { - _motSpinMin.rawValue = value + Slider { + anchors.left: parent.left + anchors.right: parent.right + minimumValue: 0 + maximumValue: Math.max(0.3, _motSpinMin.rawValue) + stepSize: 0.01 + tickmarksEnabled: true + value: _motSpinMin.rawValue + + onValueChanged: { + if (_loadComplete) { + _motSpinMin.rawValue = value + } } } } } - } - } // Rectangle - Advanced tuning - - Flow { - id: flowLayout - anchors.left: parent.left - anchors.right: parent.right - spacing: _margins + } // Rectangle - Basic tuning - Rectangle { - height: autoTuneLabel.height + autoTuneRect.height - width: autoTuneRect.width - color: palette.window - - QGCLabel { - id: autoTuneLabel - text: qsTr("AutoTune") - font.family: ScreenTools.demiboldFontFamily - } + Flow { + id: flowLayout + Layout.fillWidth: true + spacing: _margins Rectangle { - id: autoTuneRect - width: autoTuneColumn.x + autoTuneColumn.width + _margins - height: autoTuneColumn.y + autoTuneColumn.height + _margins - anchors.top: autoTuneLabel.bottom - color: palette.windowShade + height: autoTuneLabel.height + autoTuneRect.height + width: autoTuneRect.width + color: palette.window - Column { - id: autoTuneColumn - anchors.margins: _margins - anchors.left: parent.left - anchors.top: parent.top - spacing: _margins - - Row { - spacing: _margins + QGCLabel { + id: autoTuneLabel + text: qsTr("AutoTune") + font.family: ScreenTools.demiboldFontFamily + } - QGCLabel { text: qsTr("Axes to AutoTune:") } - FactBitmask { fact: _autoTuneAxes } - } + Rectangle { + id: autoTuneRect + width: autoTuneColumn.x + autoTuneColumn.width + _margins + height: autoTuneColumn.y + autoTuneColumn.height + _margins + anchors.top: autoTuneLabel.bottom + color: palette.windowShade + + Column { + id: autoTuneColumn + anchors.margins: _margins + anchors.left: parent.left + anchors.top: parent.top + spacing: _margins + + Row { + spacing: _margins + + QGCLabel { text: qsTr("Axes to AutoTune:") } + FactBitmask { fact: _autoTuneAxes } + } - Row { - spacing: _margins + Row { + spacing: _margins - QGCLabel { - anchors.baseline: autoTuneChannelCombo.baseline - text: qsTr("Channel for AutoTune switch:") - } + QGCLabel { + anchors.baseline: autoTuneChannelCombo.baseline + text: qsTr("Channel for AutoTune switch:") + } - QGCComboBox { - id: autoTuneChannelCombo - width: ScreenTools.defaultFontPixelWidth * 14 - model: [qsTr("None"), qsTr("Channel 7"), qsTr("Channel 8"), qsTr("Channel 9"), qsTr("Channel 10"), qsTr("Channel 11"), qsTr("Channel 12") ] - currentIndex: _autoTuneSwitchChannelIndex + QGCComboBox { + id: autoTuneChannelCombo + width: ScreenTools.defaultFontPixelWidth * 14 + model: [qsTr("None"), qsTr("Channel 7"), qsTr("Channel 8"), qsTr("Channel 9"), qsTr("Channel 10"), qsTr("Channel 11"), qsTr("Channel 12") ] + currentIndex: _autoTuneSwitchChannelIndex - onActivated: { - var channel = index + onActivated: { + var channel = index - if (channel > 0) { - channel += 6 + if (channel > 0) { + channel += 6 + } + setChannelAutoTuneOption(channel) } - setChannelAutoTuneOption(channel) } } } - } - } // Rectangle - AutoTune - } // Rectangle - AutoTuneWrap - - Rectangle { - height: inFlightTuneLabel.height + channel6TuningOption.height - width: channel6TuningOption.width - color: palette.window - - QGCLabel { - id: inFlightTuneLabel - text: qsTr("In Flight Tuning") - font.family: ScreenTools.demiboldFontFamily - } + } // Rectangle - AutoTune + } // Rectangle - AutoTuneWrap Rectangle { - id: channel6TuningOption - width: channel6TuningOptColumn.width + (_margins * 2) - height: channel6TuningOptColumn.height + ScreenTools.defaultFontPixelHeight - anchors.top: inFlightTuneLabel.bottom - color: qgcPal.windowShade + height: inFlightTuneLabel.height + channel6TuningOption.height + width: channel6TuningOption.width + color: palette.window - Column { - id: channel6TuningOptColumn - anchors.margins: ScreenTools.defaultFontPixelWidth - anchors.left: parent.left - anchors.top: parent.top - spacing: ScreenTools.defaultFontPixelHeight + QGCLabel { + id: inFlightTuneLabel + text: qsTr("In Flight Tuning") + font.family: ScreenTools.demiboldFontFamily + } - Row { - spacing: ScreenTools.defaultFontPixelWidth - property Fact nullFact: Fact { } + Rectangle { + id: channel6TuningOption + width: channel6TuningOptColumn.width + (_margins * 2) + height: channel6TuningOptColumn.height + ScreenTools.defaultFontPixelHeight + anchors.top: inFlightTuneLabel.bottom + color: qgcPal.windowShade + + Column { + id: channel6TuningOptColumn + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.left: parent.left + anchors.top: parent.top + spacing: ScreenTools.defaultFontPixelHeight + + Row { + spacing: ScreenTools.defaultFontPixelWidth + property Fact nullFact: Fact { } + + QGCLabel { + anchors.baseline: optCombo.baseline + text: qsTr("RC Channel 6 Option (Tuning):") + //color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text + } - QGCLabel { - anchors.baseline: optCombo.baseline - text: qsTr("RC Channel 6 Option (Tuning):") - //color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text + FactComboBox { + id: optCombo + width: ScreenTools.defaultFontPixelWidth * 15 + fact: controller.getParameterFact(-1, "TUNE") + indexModel: false + } } - FactComboBox { - id: optCombo - width: ScreenTools.defaultFontPixelWidth * 15 - fact: controller.getParameterFact(-1, "TUNE") - indexModel: false - } - } + Row { + spacing: ScreenTools.defaultFontPixelWidth + property Fact nullFact: Fact { } - Row { - spacing: ScreenTools.defaultFontPixelWidth - property Fact nullFact: Fact { } + QGCLabel { + anchors.baseline: tuneMinField.baseline + text: qsTr("Min:") + //color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text + } - QGCLabel { - anchors.baseline: tuneMinField.baseline - text: qsTr("Min:") - //color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text - } + FactTextField { + id: tuneMinField + validator: DoubleValidator {bottom: 0; top: 32767;} + fact: controller.getParameterFact(-1, "TUNE_LOW") + } - FactTextField { - id: tuneMinField - validator: DoubleValidator {bottom: 0; top: 32767;} - fact: controller.getParameterFact(-1, "TUNE_LOW") - } + QGCLabel { + anchors.baseline: tuneMaxField.baseline + text: qsTr("Max:") + //color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text + } - QGCLabel { - anchors.baseline: tuneMaxField.baseline - text: qsTr("Max:") - //color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text + FactTextField { + id: tuneMaxField + validator: DoubleValidator {bottom: 0; top: 32767;} + fact: controller.getParameterFact(-1, "TUNE_HIGH") + } } + } // Column - Channel 6 Tuning option + } // Rectangle - Channel 6 Tuning options + } // Rectangle - Channel 6 Tuning options wrap + } // Flow - Tune + } - FactTextField { - id: tuneMaxField - validator: DoubleValidator {bottom: 0; top: 32767;} - fact: controller.getParameterFact(-1, "TUNE_HIGH") - } - } - } // Column - Channel 6 Tuning option - } // Rectangle - Channel 6 Tuning options - } // Rectangle - Channel 6 Tuning options wrap - } // Flow - Tune + Loader { + anchors.left: parent.left + anchors.right: parent.right + sourceComponent: advanced ? advancePageComponent : undefined + } + + Component { + id: advancePageComponent + + PIDTuning { + anchors.left: parent.left + anchors.right: parent.right + tuneList: [ qsTr("Roll"), qsTr("Pitch"), qsTr("Yaw") ] + params: [ + [ controller.getParameterFact(-1, "ATC_ANG_RLL_P"), + controller.getParameterFact(-1, "ATC_RAT_RLL_P"), + controller.getParameterFact(-1, "ATC_RAT_RLL_I"), + controller.getParameterFact(-1, "ATC_RAT_RLL_D") ], + [ controller.getParameterFact(-1, "ATC_ANG_PIT_P"), + controller.getParameterFact(-1, "ATC_RAT_PIT_P"), + controller.getParameterFact(-1, "ATC_RAT_PIT_I"), + controller.getParameterFact(-1, "ATC_RAT_PIT_D") ], + [ controller.getParameterFact(-1, "ATC_ANG_YAW_P"), + controller.getParameterFact(-1, "ATC_RAT_YAW_P"), + controller.getParameterFact(-1, "ATC_RAT_YAW_I") ] ] + } + } // Component - Advanced Page } // Column } // Component } // SetupView diff --git a/src/QmlControls/PIDTuning.qml b/src/QmlControls/PIDTuning.qml index 6467ce0109451f4ce55df7fc6264c6d63ef1dda2..20f74c83ecf8dc35ac5c5e45acb14801ed4999e1 100644 --- a/src/QmlControls/PIDTuning.qml +++ b/src/QmlControls/PIDTuning.qml @@ -323,7 +323,7 @@ RowLayout { } Item { width: 1; height: 1 } - QGCLabel { text: qsTr("Saved Tuning Values:") } + QGCLabel { text: qsTr("Clipboard Values:") } GridLayout { rows: savedRepeater.model.length @@ -348,12 +348,12 @@ RowLayout { spacing: _margins QGCButton { - text: qsTr("Save Values") + text: qsTr("Save To Clipboard") onClicked: saveTuningParamValues() } QGCButton { - text: qsTr("Reset To Saved Values") + text: qsTr("Restore From Clipboard") onClicked: resetToSavedTuningParamValues() } }