@ -26,16 +26,13 @@ SetupPage {
@@ -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 {
@@ -69,6 +66,7 @@ SetupPage {
ExclusiveGroup { id: returnAltRadioGroup }
Component.onCompleted: {
showAdvanced = ! ScreenTools . isMobile
/ / Q m l S l i d e r s h a v e a s t r a n g e b e h a v i o r i n w h i c h t h e y f i r s t s e t S l i d e r : : v a l u e t o s o m e i n t e r n a l
/ / s e t t i n g a n d t h e n s e t S l i d e r : : v a l u e t o t h e b o u n d p r o p e r t i e s v a l u e . I f y o u h a v e a n o n V a l u e C h a n g e d
/ / h a n d l e r w h i c h u p d a t e s y o u r p r o p e r t y w i t h t h e n e w v a l u e , t h i s f i r s t v a l u e c h a n g e w i l l t r a s h
@ -76,9 +74,6 @@ SetupPage {
@@ -76,9 +74,6 @@ SetupPage {
/ / a f t e r Q m l l o a d i s d o n e . W e a l s o d o n ' t t r a c k v a l u e c h a n g e s u n t i l Q m l l o a d c o m p l e t e s .
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 {
@@ -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 gentl y" )
}
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
}
}
}
}
}
}
} / / R e c t a n g l e - B a s i c t u n i n g
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
}
}
}
}
}
}
} / / R e c t a n g l e - A d v a n c e d t u n i n g
Flow {
id: flowLayout
anchors.left: parent . left
anchors.right: parent . right
spacing: _margins
} / / R e c t a n g l e - B a s i c t u n i n g
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 )
}
}
}
}
} / / R e c t a n g l e - A u t o T u n e
} / / R e c t a n g l e - A u t o T u n e W r a p
Rectangle {
height: inFlightTuneLabel . height + channel6TuningOption . height
width: channel6TuningOption . width
color: palette . window
QGCLabel {
id: inFlightTuneLabel
text: qsTr ( "In Flight Tuning" )
font.family: ScreenTools . demiboldFontFamily
}
} / / R e c t a n g l e - A u t o T u n e
} / / R e c t a n g l e - A u t o T u n e W r a p
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):" )
/ / c o l o r : c o n t r o l l e r . c h a n n e l O p t i o n E n a b l e d [ m o d e l D a t a ] ? " y e l l o w " : q g c P a l . t e x t
}
QGCLabel {
anchors.baseline: optCombo . baseline
text: qsTr ( "RC Channel 6 Option (Tuning):" )
/ / c o l o r : c o n t r o l l e r . c h a n n e l O p t i o n E n a b l e d [ m o d e l D a t a ] ? " y e l l o w " : q g c P a l . t e x t
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:" )
/ / c o l o r : c o n t r o l l e r . c h a n n e l O p t i o n E n a b l e d [ m o d e l D a t a ] ? " y e l l o w " : q g c P a l . t e x t
}
QGCLabel {
anchors.baseline: tuneMinField . baseline
text: qsTr ( "Min:" )
/ / c o l o r : c o n t r o l l e r . c h a n n e l O p t i o n E n a b l e d [ m o d e l D a t a ] ? " y e l l o w " : q g c P a l . t e x t
}
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:" )
/ / c o l o r : c o n t r o l l e r . c h a n n e l O p t i o n E n a b l e d [ m o d e l D a t a ] ? " y e l l o w " : q g c P a l . t e x t
}
QGCLabel {
anchors.baseline: tuneMaxField . baseline
text: qsTr ( "Max:" )
/ / c o l o r : c o n t r o l l e r . c h a n n e l O p t i o n E n a b l e d [ m o d e l D a t a ] ? " y e l l o w " : q g c P a l . t e x t
FactTextField {
id: tuneMaxField
validator: DoubleValidator { bottom: 0 ; top: 32767 ; }
fact: controller . getParameterFact ( - 1 , "TUNE_HIGH" )
}
}
} / / C o l u m n - C h a n n e l 6 T u n i n g o p t i o n
} / / R e c t a n g l e - C h a n n e l 6 T u n i n g o p t i o n s
} / / R e c t a n g l e - C h a n n e l 6 T u n i n g o p t i o n s w r a p
} / / F l o w - T u n e
}
FactTextField {
id: tuneMaxField
validator: DoubleValidator { bottom: 0 ; top: 32767 ; }
fact: controller . getParameterFact ( - 1 , "TUNE_HIGH" )
}
}
} / / C o l u m n - C h a n n e l 6 T u n i n g o p t i o n
} / / R e c t a n g l e - C h a n n e l 6 T u n i n g o p t i o n s
} / / R e c t a n g l e - C h a n n e l 6 T u n i n g o p t i o n s w r a p
} / / F l o w - T u n e
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" ) ] ]
}
} / / C o m p o n e n t - A d v a n c e d P a g e
} / / C o l u m n
} / / C o m p o n e n t
} / / S e t u p V i e w