Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
9b7cfd25
Unverified
Commit
9b7cfd25
authored
Apr 05, 2018
by
Don Gagne
Committed by
GitHub
Apr 05, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6306 from DonLakeFlyer/NoMobileCharts
PID Tuning: Make QtCharts usage desktop only
parents
89ebf715
7f595c1e
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
385 additions
and
371 deletions
+385
-371
QGCSetup.pri
QGCSetup.pri
+1
-0
qgroundcontrol.pro
qgroundcontrol.pro
+1
-0
PX4TuningComponentCopter.qml
src/AutoPilotPlugins/PX4/PX4TuningComponentCopter.qml
+383
-371
No files found.
QGCSetup.pri
View file @
9b7cfd25
...
@@ -102,6 +102,7 @@ LinuxBuild {
...
@@ -102,6 +102,7 @@ LinuxBuild {
# QT_INSTALL_LIBS
# QT_INSTALL_LIBS
QT_LIB_LIST = \
QT_LIB_LIST = \
libQt5Charts.so.5 \
libQt5Core.so.5 \
libQt5Core.so.5 \
libQt5DBus.so.5 \
libQt5DBus.so.5 \
libQt5Gui.so.5 \
libQt5Gui.so.5 \
...
...
qgroundcontrol.pro
View file @
9b7cfd25
...
@@ -240,6 +240,7 @@ AndroidBuild || iOSBuild {
...
@@ -240,6 +240,7 @@ AndroidBuild || iOSBuild {
QT += \
QT += \
printsupport \
printsupport \
serialport \
serialport \
charts \
}
}
contains(DEFINES, QGC_ENABLE_BLUETOOTH) {
contains(DEFINES, QGC_ENABLE_BLUETOOTH) {
...
...
src/AutoPilotPlugins/PX4/PX4TuningComponentCopter.qml
View file @
9b7cfd25
...
@@ -28,233 +28,8 @@ SetupPage {
...
@@ -28,233 +28,8 @@ SetupPage {
Column
{
Column
{
width
:
availableWidth
width
:
availableWidth
property
real
_chartHeight
:
ScreenTools
.
defaultFontPixelHeight
*
20
property
real
_margins
:
ScreenTools
.
defaultFontPixelHeight
/
2
property
string
_currentTuneType
:
_tuneList
[
0
]
property
real
_roll
:
_activeVehicle
.
roll
.
value
property
real
_rollSetpoint
:
_activeVehicle
.
setpoint
.
roll
.
value
property
real
_rollRate
:
_activeVehicle
.
rollRate
.
value
property
real
_rollRateSetpoint
:
_activeVehicle
.
setpoint
.
rollRate
.
value
property
real
_pitch
:
_activeVehicle
.
pitch
.
value
property
real
_pitchSetpoint
:
_activeVehicle
.
setpoint
.
pitch
.
value
property
real
_pitchRate
:
_activeVehicle
.
pitchRate
.
value
property
real
_pitchRateSetpoint
:
_activeVehicle
.
setpoint
.
pitchRate
.
value
property
real
_yaw
:
_activeVehicle
.
heading
.
value
property
real
_yawSetpoint
:
_activeVehicle
.
setpoint
.
yaw
.
value
property
real
_yawRate
:
_activeVehicle
.
yawRate
.
value
property
real
_yawRateSetpoint
:
_activeVehicle
.
setpoint
.
yawRate
.
value
property
var
_valueXAxis
:
valueXAxis
property
var
_valueRateXAxis
:
valueRateXAxis
property
var
_valueYAxis
:
valueYAxis
property
var
_valueRateYAxis
:
valueRateYAxis
property
int
_msecs
:
0
property
var
_savedTuningParamValues
:
[
]
// The following are set when getValues is called
property
real
_value
property
real
_valueSetpoint
property
real
_valueRate
property
real
_valueRateSetpoint
readonly
property
int
_tickSeparation
:
5
readonly
property
int
_tuneListRollIndex
:
0
readonly
property
int
_tuneListPitchIndex
:
1
readonly
property
int
_tuneListYawIndex
:
2
readonly
property
var
_tuneList
:
[
qsTr
(
"
Roll
"
),
qsTr
(
"
Pitch
"
),
qsTr
(
"
Yaw
"
)
]
readonly
property
var
_params
:
[
[
controller
.
getParameterFact
(
-
1
,
"
MC_ROLL_P
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_ROLLRATE_P
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_ROLLRATE_I
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_ROLLRATE_D
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_ROLLRATE_FF
"
)
],
[
controller
.
getParameterFact
(
-
1
,
"
MC_PITCH_P
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_PITCHRATE_P
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_PITCHRATE_I
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_PITCHRATE_D
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_PITCHRATE_FF
"
)
],
[
controller
.
getParameterFact
(
-
1
,
"
MC_YAW_P
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_YAWRATE_P
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_YAWRATE_I
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_YAWRATE_D
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_YAW_FF
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_YAWRATE_FF
"
)
]
]
function
adjustYAxisMin
(
yAxis
,
newValue
)
{
var
newMin
=
Math
.
min
(
yAxis
.
min
,
newValue
)
if
(
newMin
%
5
!=
0
)
{
newMin
-=
5
newMin
=
Math
.
floor
(
newMin
/
_tickSeparation
)
*
_tickSeparation
}
yAxis
.
min
=
newMin
}
function
adjustYAxisMax
(
yAxis
,
newValue
)
{
var
newMax
=
Math
.
max
(
yAxis
.
max
,
newValue
)
if
(
newMax
%
5
!=
0
)
{
newMax
+=
5
newMax
=
Math
.
floor
(
newMax
/
_tickSeparation
)
*
_tickSeparation
}
yAxis
.
max
=
newMax
}
function
getValues
()
{
if
(
_currentTuneType
===
_tuneList
[
_tuneListRollIndex
])
{
_value
=
_roll
_valueSetpoint
=
_rollSetpoint
_valueRate
=
_rollRate
_valueRateSetpoint
=
_rollRateSetpoint
}
else
if
(
_currentTuneType
===
_tuneList
[
_tuneListPitchIndex
])
{
_value
=
_pitch
_valueSetpoint
=
_pitchSetpoint
_valueRate
=
_pitchRate
_valueRateSetpoint
=
_pitchRateSetpoint
}
else
if
(
_currentTuneType
===
_tuneList
[
_tuneListYawIndex
])
{
_value
=
_yaw
_valueSetpoint
=
_yawSetpoint
_valueRate
=
_yawRate
_valueRateSetpoint
=
_yawRateSetpoint
}
}
function
resetGraphs
()
{
valueSeries
.
removePoints
(
0
,
valueSeries
.
count
)
valueSetpointSeries
.
removePoints
(
0
,
valueSetpointSeries
.
count
)
valueRateSeries
.
removePoints
(
0
,
valueRateSeries
.
count
)
valueRateSetpointSeries
.
removePoints
(
0
,
valueRateSetpointSeries
.
count
)
_valueXAxis
.
min
=
0
_valueXAxis
.
max
=
0
_valueRateXAxis
.
min
=
0
_valueRateXAxis
.
max
=
0
_valueYAxis
.
min
=
0
_valueYAxis
.
max
=
10
_valueRateYAxis
.
min
=
0
_valueRateYAxis
.
max
=
10
_msecs
=
0
}
function
currentTuneTypeIndex
()
{
if
(
_currentTuneType
===
_tuneList
[
_tuneListRollIndex
])
{
return
_tuneListRollIndex
}
else
if
(
_currentTuneType
===
_tuneList
[
_tuneListPitchIndex
])
{
return
_tuneListPitchIndex
}
else
if
(
_currentTuneType
===
_tuneList
[
_tuneListYawIndex
])
{
return
_tuneListYawIndex
}
}
// Save the current set of tuning values so we can reset to them
function
saveTuningParamValues
()
{
var
tuneTypeIndex
=
currentTuneTypeIndex
()
_savedTuningParamValues
=
[
]
var
currentTuneParams
=
_params
[
tuneTypeIndex
]
for
(
var
i
=
0
;
i
<
currentTuneParams
.
length
;
i
++
)
{
_savedTuningParamValues
.
push
(
currentTuneParams
[
i
].
valueString
)
}
savedRepeater
.
model
=
_savedTuningParamValues
}
function
resetToSavedTuningParamValues
()
{
var
tuneTypeIndex
=
currentTuneTypeIndex
()
for
(
var
i
=
0
;
i
<
_savedTuningParamValues
.
length
;
i
++
)
{
_params
[
tuneTypeIndex
][
i
].
value
=
_savedTuningParamValues
[
i
]
}
}
Component.onCompleted
:
{
Component.onCompleted
:
{
showAdvanced
=
true
showAdvanced
=
!
ScreenTools
.
isMobile
saveTuningParamValues
()
}
on_CurrentTuneTypeChanged
:
{
saveTuningParamValues
()
resetGraphs
()
}
FactPanelController
{
id
:
controller
factPanel
:
tuningPage
.
viewPanel
}
ExclusiveGroup
{
id
:
tuneTypeRadios
}
ValueAxis
{
id
:
valueXAxis
min
:
0
max
:
0
labelFormat
:
"
%d
"
titleText
:
"
sec
"
}
ValueAxis
{
id
:
valueRateXAxis
min
:
0
max
:
0
labelFormat
:
"
%d
"
titleText
:
"
sec
"
}
ValueAxis
{
id
:
valueYAxis
min
:
0
max
:
10
titleText
:
"
deg
"
tickCount
:
((
max
-
min
)
/
_tickSeparation
)
+
1
}
ValueAxis
{
id
:
valueRateYAxis
min
:
0
max
:
10
titleText
:
"
deg/s
"
tickCount
:
((
max
-
min
)
/
_tickSeparation
)
+
1
}
Timer
{
id
:
dataTimer
interval
:
50
running
:
false
repeat
:
true
onTriggered
:
{
var
seconds
=
_msecs
/
1000
_valueXAxis
.
max
=
seconds
_valueRateXAxis
.
max
=
seconds
getValues
()
valueSeries
.
append
(
seconds
,
_value
)
adjustYAxisMin
(
_valueYAxis
,
_value
)
adjustYAxisMax
(
_valueYAxis
,
_value
)
valueSetpointSeries
.
append
(
seconds
,
_valueSetpoint
)
adjustYAxisMin
(
_valueYAxis
,
_valueSetpoint
)
adjustYAxisMax
(
_valueYAxis
,
_valueSetpoint
)
valueRateSeries
.
append
(
seconds
,
_valueRate
)
adjustYAxisMin
(
_valueRateYAxis
,
_valueRate
)
adjustYAxisMax
(
_valueRateYAxis
,
_valueRate
)
valueRateSetpointSeries
.
append
(
seconds
,
_valueRateSetpoint
)
adjustYAxisMin
(
_valueRateYAxis
,
_valueRateSetpoint
)
adjustYAxisMax
(
_valueRateYAxis
,
_valueRateSetpoint
)
_msecs
+=
interval
if
(
valueSeries
.
count
>
_maxPointCount
)
{
valueSeries
.
remove
(
0
)
valueSetpointSeries
.
remove
(
0
)
valueRateSeries
.
remove
(
0
)
valueRateSetpointSeries
.
remove
(
0
)
valueXAxis
.
min
=
valueSeries
.
at
(
0
).
x
valueRateXAxis
.
min
=
valueSeries
.
at
(
0
).
x
}
}
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
property
int
_maxPointCount
:
10000
/
interval
}
}
// Standard tuning page
// Standard tuning page
...
@@ -281,7 +56,7 @@ SetupPage {
...
@@ -281,7 +56,7 @@ SetupPage {
max
:
15
max
:
15
step
:
1
step
:
1
}
}
/*
/*
These seem to have disappeared from PX4 firmware!
These seem to have disappeared from PX4 firmware!
ListElement {
ListElement {
title: qsTr("Roll sensitivity")
title: qsTr("Roll sensitivity")
...
@@ -304,207 +79,444 @@ SetupPage {
...
@@ -304,207 +79,444 @@ SetupPage {
}
}
}
}
// Advanced page
Loader
{
RowLayout
{
anchors.left
:
parent
.
left
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.right
:
parent
.
right
layoutDirection
:
Qt
.
RightToLeft
sourceComponent
:
advanced
?
advancePageComponent
:
undefined
visible
:
advanced
}
Component
{
id
:
advancePageComponent
// Advanced page
RowLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
layoutDirection
:
Qt
.
RightToLeft
property
real
_chartHeight
:
ScreenTools
.
defaultFontPixelHeight
*
20
property
real
_margins
:
ScreenTools
.
defaultFontPixelHeight
/
2
property
string
_currentTuneType
:
_tuneList
[
0
]
property
real
_roll
:
_activeVehicle
.
roll
.
value
property
real
_rollSetpoint
:
_activeVehicle
.
setpoint
.
roll
.
value
property
real
_rollRate
:
_activeVehicle
.
rollRate
.
value
property
real
_rollRateSetpoint
:
_activeVehicle
.
setpoint
.
rollRate
.
value
property
real
_pitch
:
_activeVehicle
.
pitch
.
value
property
real
_pitchSetpoint
:
_activeVehicle
.
setpoint
.
pitch
.
value
property
real
_pitchRate
:
_activeVehicle
.
pitchRate
.
value
property
real
_pitchRateSetpoint
:
_activeVehicle
.
setpoint
.
pitchRate
.
value
property
real
_yaw
:
_activeVehicle
.
heading
.
value
property
real
_yawSetpoint
:
_activeVehicle
.
setpoint
.
yaw
.
value
property
real
_yawRate
:
_activeVehicle
.
yawRate
.
value
property
real
_yawRateSetpoint
:
_activeVehicle
.
setpoint
.
yawRate
.
value
property
var
_valueXAxis
:
valueXAxis
property
var
_valueRateXAxis
:
valueRateXAxis
property
var
_valueYAxis
:
valueYAxis
property
var
_valueRateYAxis
:
valueRateYAxis
property
int
_msecs
:
0
property
var
_savedTuningParamValues
:
[
]
// The following are set when getValues is called
property
real
_value
property
real
_valueSetpoint
property
real
_valueRate
property
real
_valueRateSetpoint
readonly
property
int
_tickSeparation
:
5
readonly
property
int
_tuneListRollIndex
:
0
readonly
property
int
_tuneListPitchIndex
:
1
readonly
property
int
_tuneListYawIndex
:
2
readonly
property
var
_tuneList
:
[
qsTr
(
"
Roll
"
),
qsTr
(
"
Pitch
"
),
qsTr
(
"
Yaw
"
)
]
readonly
property
var
_params
:
[
[
controller
.
getParameterFact
(
-
1
,
"
MC_ROLL_P
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_ROLLRATE_P
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_ROLLRATE_I
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_ROLLRATE_D
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_ROLLRATE_FF
"
)
],
[
controller
.
getParameterFact
(
-
1
,
"
MC_PITCH_P
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_PITCHRATE_P
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_PITCHRATE_I
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_PITCHRATE_D
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_PITCHRATE_FF
"
)
],
[
controller
.
getParameterFact
(
-
1
,
"
MC_YAW_P
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_YAWRATE_P
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_YAWRATE_I
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_YAWRATE_D
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_YAW_FF
"
),
controller
.
getParameterFact
(
-
1
,
"
MC_YAWRATE_FF
"
)
]
]
function
adjustYAxisMin
(
yAxis
,
newValue
)
{
var
newMin
=
Math
.
min
(
yAxis
.
min
,
newValue
)
if
(
newMin
%
5
!=
0
)
{
newMin
-=
5
newMin
=
Math
.
floor
(
newMin
/
_tickSeparation
)
*
_tickSeparation
}
yAxis
.
min
=
newMin
}
Column
{
function
adjustYAxisMax
(
yAxis
,
newValue
)
{
spacing
:
_margins
var
newMax
=
Math
.
max
(
yAxis
.
max
,
newValue
)
Layout.alignment
:
Qt
.
AlignTop
if
(
newMax
%
5
!=
0
)
{
newMax
+=
5
newMax
=
Math
.
floor
(
newMax
/
_tickSeparation
)
*
_tickSeparation
}
yAxis
.
max
=
newMax
}
QGCLabel
{
text
:
qsTr
(
"
Tuning Axis:
"
)
}
function
getValues
()
{
if
(
_currentTuneType
===
_tuneList
[
_tuneListRollIndex
])
{
_value
=
_roll
_valueSetpoint
=
_rollSetpoint
_valueRate
=
_rollRate
_valueRateSetpoint
=
_rollRateSetpoint
}
else
if
(
_currentTuneType
===
_tuneList
[
_tuneListPitchIndex
])
{
_value
=
_pitch
_valueSetpoint
=
_pitchSetpoint
_valueRate
=
_pitchRate
_valueRateSetpoint
=
_pitchRateSetpoint
}
else
if
(
_currentTuneType
===
_tuneList
[
_tuneListYawIndex
])
{
_value
=
_yaw
_valueSetpoint
=
_yawSetpoint
_valueRate
=
_yawRate
_valueRateSetpoint
=
_yawRateSetpoint
}
}
RowLayout
{
function
resetGraphs
()
{
spacing
:
_margins
valueSeries
.
removePoints
(
0
,
valueSeries
.
count
)
valueSetpointSeries
.
removePoints
(
0
,
valueSetpointSeries
.
count
)
valueRateSeries
.
removePoints
(
0
,
valueRateSeries
.
count
)
valueRateSetpointSeries
.
removePoints
(
0
,
valueRateSetpointSeries
.
count
)
_valueXAxis
.
min
=
0
_valueXAxis
.
max
=
0
_valueRateXAxis
.
min
=
0
_valueRateXAxis
.
max
=
0
_valueYAxis
.
min
=
0
_valueYAxis
.
max
=
10
_valueRateYAxis
.
min
=
0
_valueRateYAxis
.
max
=
10
_msecs
=
0
}
Repeater
{
function
currentTuneTypeIndex
()
{
model
:
_tuneList
if
(
_currentTuneType
===
_tuneList
[
_tuneListRollIndex
])
{
QGCRadioButton
{
return
_tuneListRollIndex
text
:
modelData
}
else
if
(
_currentTuneType
===
_tuneList
[
_tuneListPitchIndex
])
{
checked
:
_currentTuneType
===
modelData
return
_tuneListPitchIndex
exclusiveGroup
:
tuneTypeRadios
}
else
if
(
_currentTuneType
===
_tuneList
[
_tuneListYawIndex
])
{
return
_tuneListYawIndex
}
}
onClicked
:
_currentTuneType
=
modelData
// Save the current set of tuning values so we can reset to them
}
function
saveTuningParamValues
()
{
var
tuneTypeIndex
=
currentTuneTypeIndex
()
_savedTuningParamValues
=
[
]
var
currentTuneParams
=
_params
[
tuneTypeIndex
]
for
(
var
i
=
0
;
i
<
currentTuneParams
.
length
;
i
++
)
{
_savedTuningParamValues
.
push
(
currentTuneParams
[
i
].
valueString
)
}
}
savedRepeater
.
model
=
_savedTuningParamValues
}
}
Item
{
width
:
1
;
height
:
1
}
function
resetToSavedTuningParamValues
()
{
var
tuneTypeIndex
=
currentTuneTypeIndex
()
QGCLabel
{
text
:
qsTr
(
"
Tuning Values:
"
)
}
for
(
var
i
=
0
;
i
<
_savedTuningParamValues
.
length
;
i
++
)
{
_params
[
tuneTypeIndex
][
i
].
value
=
_savedTuningParamValues
[
i
]
}
}
GridLayout
{
Component.onCompleted
:
{
rows
:
factList
.
length
saveTuningParamValues
()
flow
:
GridLayout
.
TopToBottom
}
rowSpacing
:
_margins
columnSpacing
:
_margins
property
var
factList
:
_params
[
_tuneList
.
indexOf
(
_currentTuneType
)]
on_CurrentTuneTypeChanged
:
{
saveTuningParamValues
()
resetGraphs
()
}
Repeater
{
FactPanelController
{
model
:
parent
.
factList
id
:
controller
factPanel
:
tuningPage
.
viewPanel
}
QGCLabel
{
text
:
modelData
.
name
}
ExclusiveGroup
{
id
:
tuneTypeRadios
}
ValueAxis
{
id
:
valueXAxis
min
:
0
max
:
0
labelFormat
:
"
%d
"
titleText
:
"
sec
"
}
ValueAxis
{
id
:
valueRateXAxis
min
:
0
max
:
0
labelFormat
:
"
%d
"
titleText
:
"
sec
"
}
ValueAxis
{
id
:
valueYAxis
min
:
0
max
:
10
titleText
:
"
deg
"
tickCount
:
((
max
-
min
)
/
_tickSeparation
)
+
1
}
ValueAxis
{
id
:
valueRateYAxis
min
:
0
max
:
10
titleText
:
"
deg/s
"
tickCount
:
((
max
-
min
)
/
_tickSeparation
)
+
1
}
Timer
{
id
:
dataTimer
interval
:
50
running
:
false
repeat
:
true
onTriggered
:
{
var
seconds
=
_msecs
/
1000
_valueXAxis
.
max
=
seconds
_valueRateXAxis
.
max
=
seconds
getValues
()
valueSeries
.
append
(
seconds
,
_value
)
adjustYAxisMin
(
_valueYAxis
,
_value
)
adjustYAxisMax
(
_valueYAxis
,
_value
)
valueSetpointSeries
.
append
(
seconds
,
_valueSetpoint
)
adjustYAxisMin
(
_valueYAxis
,
_valueSetpoint
)
adjustYAxisMax
(
_valueYAxis
,
_valueSetpoint
)
valueRateSeries
.
append
(
seconds
,
_valueRate
)
adjustYAxisMin
(
_valueRateYAxis
,
_valueRate
)
adjustYAxisMax
(
_valueRateYAxis
,
_valueRate
)
valueRateSetpointSeries
.
append
(
seconds
,
_valueRateSetpoint
)
adjustYAxisMin
(
_valueRateYAxis
,
_valueRateSetpoint
)
adjustYAxisMax
(
_valueRateYAxis
,
_valueRateSetpoint
)
_msecs
+=
interval
if
(
valueSeries
.
count
>
_maxPointCount
)
{
valueSeries
.
remove
(
0
)
valueSetpointSeries
.
remove
(
0
)
valueRateSeries
.
remove
(
0
)
valueRateSetpointSeries
.
remove
(
0
)
valueXAxis
.
min
=
valueSeries
.
at
(
0
).
x
valueRateXAxis
.
min
=
valueSeries
.
at
(
0
).
x
}
}
}
Repeater
{
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
model
:
parent
.
factList
property
int
_maxPointCount
:
10000
/
interval
}
QGCButton
{
Column
{
text
:
"
-
"
spacing
:
_margins
onClicked
:
{
Layout.alignment
:
Qt
.
AlignTop
var
value
=
modelData
.
value
modelData
.
value
-=
value
*
adjustPercentModel
.
get
(
adjustPercentCombo
.
currentIndex
).
value
QGCLabel
{
text
:
qsTr
(
"
Tuning Axis:
"
)
}
RowLayout
{
spacing
:
_margins
Repeater
{
model
:
_tuneList
QGCRadioButton
{
text
:
modelData
checked
:
_currentTuneType
===
modelData
exclusiveGroup
:
tuneTypeRadios
onClicked
:
_currentTuneType
=
modelData
}
}
}
}
}
}
Repeater
{
Item
{
width
:
1
;
height
:
1
}
model
:
parent
.
factList
QGCLabel
{
text
:
qsTr
(
"
Tuning Values:
"
)
}
FactTextField
{
GridLayout
{
Layout.fillWidth
:
true
rows
:
factList
.
length
fact
:
modelData
flow
:
GridLayout
.
TopToBottom
showUnits
:
false
rowSpacing
:
_margins
columnSpacing
:
_margins
property
var
factList
:
_params
[
_tuneList
.
indexOf
(
_currentTuneType
)]
Repeater
{
model
:
parent
.
factList
QGCLabel
{
text
:
modelData
.
name
}
}
}
}
Repeater
{
Repeater
{
model
:
parent
.
factList
model
:
parent
.
factList
QGCButton
{
QGCButton
{
text
:
"
+
"
text
:
"
-
"
onClicked
:
{
onClicked
:
{
var
value
=
modelData
.
value
var
value
=
modelData
.
value
modelData
.
value
+=
value
*
adjustPercentModel
.
get
(
adjustPercentCombo
.
currentIndex
).
value
modelData
.
value
-=
value
*
adjustPercentModel
.
get
(
adjustPercentCombo
.
currentIndex
).
value
}
}
}
Repeater
{
model
:
parent
.
factList
FactTextField
{
Layout.fillWidth
:
true
fact
:
modelData
showUnits
:
false
}
}
Repeater
{
model
:
parent
.
factList
QGCButton
{
text
:
"
+
"
onClicked
:
{
var
value
=
modelData
.
value
modelData
.
value
+=
value
*
adjustPercentModel
.
get
(
adjustPercentCombo
.
currentIndex
).
value
}
}
}
}
}
}
}
}
RowLayout
{
RowLayout
{
QGCLabel
{
text
:
qsTr
(
"
Increment/Decrement %
"
)
}
QGCLabel
{
text
:
qsTr
(
"
Increment/Decrement %
"
)
}
QGCComboBox
{
QGCComboBox
{
id
:
adjustPercentCombo
id
:
adjustPercentCombo
model
:
ListModel
{
model
:
ListModel
{
id
:
adjustPercentModel
id
:
adjustPercentModel
ListElement
{
text
:
"
5
"
;
value
:
0.05
}
ListElement
{
text
:
"
5
"
;
value
:
0.05
}
ListElement
{
text
:
"
10
"
;
value
:
0.10
}
ListElement
{
text
:
"
10
"
;
value
:
0.10
}
ListElement
{
text
:
"
15
"
;
value
:
0.15
}
ListElement
{
text
:
"
15
"
;
value
:
0.15
}
ListElement
{
text
:
"
20
"
;
value
:
0.20
}
ListElement
{
text
:
"
20
"
;
value
:
0.20
}
}
}
}
}
}
}
Item
{
width
:
1
;
height
:
1
}
Item
{
width
:
1
;
height
:
1
}
QGCLabel
{
text
:
qsTr
(
"
Saved Tuning Values:
"
)
}
QGCLabel
{
text
:
qsTr
(
"
Saved Tuning Values:
"
)
}
GridLayout
{
GridLayout
{
rows
:
savedRepeater
.
model
.
length
rows
:
savedRepeater
.
model
.
length
flow
:
GridLayout
.
TopToBottom
flow
:
GridLayout
.
TopToBottom
rowSpacing
:
_margins
rowSpacing
:
_margins
columnSpacing
:
_margins
columnSpacing
:
_margins
Repeater
{
Repeater
{
model
:
_params
[
_tuneList
.
indexOf
(
_currentTuneType
)]
model
:
_params
[
_tuneList
.
indexOf
(
_currentTuneType
)]
QGCLabel
{
text
:
modelData
.
name
}
QGCLabel
{
text
:
modelData
.
name
}
}
}
Repeater
{
Repeater
{
id
:
savedRepeater
id
:
savedRepeater
QGCLabel
{
text
:
modelData
}
QGCLabel
{
text
:
modelData
}
}
}
}
}
RowLayout
{
RowLayout
{
spacing
:
_margins
spacing
:
_margins
QGCButton
{
QGCButton
{
text
:
qsTr
(
"
Save Values
"
)
text
:
qsTr
(
"
Save Values
"
)
onClicked
:
saveTuningParamValues
()
onClicked
:
saveTuningParamValues
()
}
}
QGCButton
{
QGCButton
{
text
:
qsTr
(
"
Reset To Saved Values
"
)
text
:
qsTr
(
"
Reset To Saved Values
"
)
onClicked
:
resetToSavedTuningParamValues
()
onClicked
:
resetToSavedTuningParamValues
()
}
}
}
}
Item
{
width
:
1
;
height
:
1
}
Item
{
width
:
1
;
height
:
1
}
QGCLabel
{
text
:
qsTr
(
"
Chart:
"
)
}
QGCLabel
{
text
:
qsTr
(
"
Chart:
"
)
}
RowLayout
{
RowLayout
{
spacing
:
_margins
spacing
:
_margins
QGCButton
{
QGCButton
{
text
:
qsTr
(
"
Clear
"
)
text
:
qsTr
(
"
Clear
"
)
onClicked
:
resetGraphs
()
onClicked
:
resetGraphs
()
}
}
QGCButton
{
QGCButton
{
text
:
dataTimer
.
running
?
qsTr
(
"
Stop
"
)
:
qsTr
(
"
Start
"
)
text
:
dataTimer
.
running
?
qsTr
(
"
Stop
"
)
:
qsTr
(
"
Start
"
)
onClicked
:
dataTimer
.
running
=
!
dataTimer
.
running
onClicked
:
dataTimer
.
running
=
!
dataTimer
.
running
}
}
}
}
}
}
Column
{
Column
{
Layout.fillWidth
:
true
Layout.fillWidth
:
true
ChartView
{
ChartView
{
anchors.left
:
parent
.
left
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.right
:
parent
.
right
height
:
availableHeight
/
2
height
:
availableHeight
/
2
title
:
_currentTuneType
title
:
_currentTuneType
antialiasing
:
true
antialiasing
:
true
legend.alignment
:
Qt
.
AlignRight
legend.alignment
:
Qt
.
AlignRight
LineSeries
{
LineSeries
{
id
:
valueSeries
id
:
valueSeries
name
:
"
Response
"
name
:
"
Response
"
axisY
:
valueYAxis
axisY
:
valueYAxis
axisX
:
valueXAxis
axisX
:
valueXAxis
}
}
LineSeries
{
LineSeries
{
id
:
valueSetpointSeries
id
:
valueSetpointSeries
name
:
"
Command
"
name
:
"
Command
"
axisY
:
valueYAxis
axisY
:
valueYAxis
axisX
:
valueXAxis
axisX
:
valueXAxis
}
}
}
}
ChartView
{
ChartView
{
anchors.left
:
parent
.
left
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.right
:
parent
.
right
height
:
availableHeight
/
2
height
:
availableHeight
/
2
title
:
_currentTuneType
+
qsTr
(
"
Rate
"
)
title
:
_currentTuneType
+
qsTr
(
"
Rate
"
)
antialiasing
:
true
antialiasing
:
true
legend.alignment
:
Qt
.
AlignRight
legend.alignment
:
Qt
.
AlignRight
LineSeries
{
LineSeries
{
id
:
valueRateSeries
id
:
valueRateSeries
name
:
"
Response
"
name
:
"
Response
"
axisY
:
valueRateYAxis
axisY
:
valueRateYAxis
axisX
:
valueRateXAxis
axisX
:
valueRateXAxis
}
}
LineSeries
{
LineSeries
{
id
:
valueRateSetpointSeries
id
:
valueRateSetpointSeries
name
:
"
Command
"
name
:
"
Command
"
axisY
:
valueRateYAxis
axisY
:
valueRateYAxis
axisX
:
valueRateXAxis
axisX
:
valueRateXAxis
}
}
}
}
}
}
}
// RowLayout - Advanced Page
}
//
RowLayou
t - Advanced Page
}
//
Componen
t - Advanced Page
}
// Column
}
// Column
}
// Component - pageComponent
}
// Component - pageComponent
}
// SetupPage
}
// SetupPage
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment