@ -27,15 +27,12 @@ SetupPage {
@@ -27,15 +27,12 @@ SetupPage {
Column {
width: availableWidth
spacing: _margins
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,6 +119,12 @@ SetupPage {
@@ -124,6 +119,12 @@ SetupPage {
Connections { target: _ch11Opt ; onValueChanged: calcAutoTuneChannel ( ) }
Connections { target: _ch12Opt ; onValueChanged: calcAutoTuneChannel ( ) }
Column {
anchors.left: parent . left
anchors.right: parent . right
spacing: _margins
visible: ! advanced
QGCLabel {
text: qsTr ( "Basic Tuning" )
font.family: ScreenTools . demiboldFontFamily
@ -212,37 +213,6 @@ SetupPage {
@@ -212,37 +213,6 @@ SetupPage {
Column {
anchors.left: parent . left
anchors.right: parent . right
visible: _rcFeelAvailable
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" )
}
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
}
}
}
}
Column {
anchors.left: parent . left
anchors.right: parent . right
visible: _atcInputTCAvailable
QGCLabel {
@ -270,30 +240,10 @@ SetupPage {
@@ -270,30 +240,10 @@ SetupPage {
}
}
}
}
} / / 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
Column {
anchors.left: parent . left
anchors.right: parent . right
anchors.top: parent . top
spacing: _margins
Column {
Layout.fillWidth: true
QGCLabel {
text: qsTr ( "Spin While Armed" )
@ -322,8 +272,8 @@ SetupPage {
@@ -322,8 +272,8 @@ SetupPage {
}
Column {
id: lastAdvTuningColumn
Layout.fillWidth: true
anchors.left: parent . left
anchors.right: parent . right
QGCLabel {
text: qsTr ( "Minimum Thrust" )
@ -331,7 +281,7 @@ SetupPage {
@@ -331,7 +281,7 @@ SetupPage {
}
QGCLabel {
text: qsTr ( "Adjust the minimum amount of thrust for a stable minimum throttle descent " )
text: qsTr ( "Adjust the minimum amount of thrust require for the vehicle to move " )
}
QGCLabel {
@ -357,12 +307,11 @@ SetupPage {
@@ -357,12 +307,11 @@ SetupPage {
}
}
}
} / / R e c t a n g l e - A d v a n c e d t u n i n g
} / / R e c t a n g l e - B a s i c t u n i n g
Flow {
id: flowLayout
anchors.left: parent . left
anchors.right: parent . right
Layout.fillWidth: true
spacing: _margins
Rectangle {
@ -500,6 +449,35 @@ SetupPage {
@@ -500,6 +449,35 @@ SetupPage {
} / / 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