PIDTuning.qml 14.2 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

import QtQuick          2.3
import QtQuick.Controls 1.2
import QtCharts         2.2
import QtQuick.Layouts  1.2

import QGroundControl               1.0
import QGroundControl.Controls      1.0
import QGroundControl.FactSystem    1.0
import QGroundControl.FactControls  1.0
import QGroundControl.ScreenTools   1.0

RowLayout {
    layoutDirection: Qt.RightToLeft

    property var tuneList
    property var params

    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 _maxTickSections:     10
    readonly property int _tuneListRollIndex:   0
    readonly property int _tuneListPitchIndex:  1
    readonly property int _tuneListYawIndex:    2

    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: {
Don Gagne's avatar
Don Gagne committed
145
        _activeVehicle.setPIDTuningTelemetryMode(true)
146 147 148
        saveTuningParamValues()
    }

149
    Component.onDestruction: _activeVehicle.setPIDTuningTelemetryMode(false)
150

151 152 153 154 155 156 157 158 159 160 161 162 163 164
    on_CurrentTuneTypeChanged: {
        saveTuningParamValues()
        resetGraphs()
    }

    ExclusiveGroup {
        id: tuneTypeRadios
    }

    ValueAxis {
        id:             valueXAxis
        min:            0
        max:            0
        labelFormat:    "%d"
165 166
        titleText:      "msec"
        tickCount:      11
167 168 169 170 171 172 173
    }

    ValueAxis {
        id:             valueRateXAxis
        min:            0
        max:            0
        labelFormat:    "%d"
174 175
        titleText:      "msec"
        tickCount:      11
176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200
    }

    ValueAxis {
        id:         valueYAxis
        min:        0
        max:        10
        titleText:  "deg"
        tickCount:  Math.min(((max - min) / _tickSeparation), _maxTickSections) + 1
    }

    ValueAxis {
        id:         valueRateYAxis
        min:        0
        max:        10
        titleText:  "deg/s"
        tickCount:  Math.min(((max - min) / _tickSeparation), _maxTickSections) + 1
    }

    Timer {
        id:         dataTimer
        interval:   10
        running:    false
        repeat:     true

        onTriggered: {
201 202
            _valueXAxis.max = _msecs
            _valueRateXAxis.max = _msecs
203 204 205

            getValues()

206
            valueSeries.append(_msecs, _value)
207 208 209
            adjustYAxisMin(_valueYAxis, _value)
            adjustYAxisMax(_valueYAxis, _value)

210
            valueSetpointSeries.append(_msecs, _valueSetpoint)
211 212 213
            adjustYAxisMin(_valueYAxis, _valueSetpoint)
            adjustYAxisMax(_valueYAxis, _valueSetpoint)

214
            valueRateSeries.append(_msecs, _valueRate)
215 216 217
            adjustYAxisMin(_valueRateYAxis, _valueRate)
            adjustYAxisMax(_valueRateYAxis, _valueRate)

218
            valueRateSetpointSeries.append(_msecs, _valueRateSetpoint)
219 220 221 222 223 224 225 226 227 228 229 230 231 232
            adjustYAxisMin(_valueRateYAxis, _valueRateSetpoint)
            adjustYAxisMax(_valueRateYAxis, _valueRateSetpoint)

            _msecs += interval
        }

        property var _activeVehicle:    QGroundControl.multiVehicleManager.activeVehicle
        property int _maxPointCount:    10000 / interval
    }

    Column {
        spacing:            _margins
        Layout.alignment:   Qt.AlignTop

233 234
        Column {
            QGCLabel { text: qsTr("Tuning Axis:") }
235

236 237
            RowLayout {
                spacing: _margins
238

239 240 241 242 243 244
                Repeater {
                    model: tuneList
                    QGCRadioButton {
                        text:           modelData
                        checked:        _currentTuneType === modelData
                        exclusiveGroup: tuneTypeRadios
245

246 247
                        onClicked: _currentTuneType = modelData
                    }
248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274
                }
            }
        }

        QGCLabel { text: qsTr("Tuning Values:") }

        GridLayout {
            rows:           factList.length
            flow:           GridLayout.TopToBottom
            rowSpacing:     _margins
            columnSpacing:  _margins

            property var factList: params[tuneList.indexOf(_currentTuneType)]

            Repeater {
                model: parent.factList

                QGCLabel { text: modelData.name }
            }

            Repeater {
                model: parent.factList

                QGCButton {
                    text: "-"
                    onClicked: {
                        var value = modelData.value
275 276 277 278
                        var newValue = value - (value * adjustPercentModel.get(adjustPercentCombo.currentIndex).value)
                        if (newValue >= modelData.min) {
                            modelData.value = newValue
                        }
279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299
                    }
                }
            }

            Repeater {
                model: parent.factList

                FactTextField {
                    Layout.fillWidth:   true
                    fact:               modelData
                    showUnits:          false
                }
            }

            Repeater {
                model: parent.factList

                QGCButton {
                    text: "+"
                    onClicked: {
                        var value = modelData.value
300 301 302 303
                        var newValue = value + (value * adjustPercentModel.get(adjustPercentCombo.currentIndex).value)
                        if (newValue <= modelData.max) {
                            modelData.value = newValue
                        }
304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323
                    }
                }
            }
        }

        RowLayout {
            QGCLabel { text: qsTr("Increment/Decrement %") }

            QGCComboBox {
                id:     adjustPercentCombo
                model:  ListModel {
                    id: adjustPercentModel
                    ListElement { text: "5"; value: 0.05 }
                    ListElement { text: "10"; value: 0.10 }
                    ListElement { text: "15"; value: 0.15 }
                    ListElement { text: "20"; value: 0.20 }
                }
            }
        }

324 325
        Column {
            QGCLabel { text: qsTr("Clipboard Values:") }
326

327 328 329 330 331
            GridLayout {
                rows:           savedRepeater.model.length
                flow:           GridLayout.TopToBottom
                rowSpacing:     0
                columnSpacing:  _margins
332

333 334
                Repeater {
                    model: params[tuneList.indexOf(_currentTuneType)]
335

336 337
                    QGCLabel { text: modelData.name }
                }
338

339 340
                Repeater {
                    id: savedRepeater
341

342 343
                    QGCLabel { text: modelData }
                }
344 345 346 347 348 349 350
            }
        }

        RowLayout {
            spacing: _margins

            QGCButton {
351
                text:       qsTr("Save To Clipboard")
352 353 354 355
                onClicked:  saveTuningParamValues()
            }

            QGCButton {
356
                text:       qsTr("Restore From Clipboard")
357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374
                onClicked:  resetToSavedTuningParamValues()
            }
        }

        Item { width: 1; height: 1 }

        QGCLabel { text: qsTr("Chart:") }

        RowLayout {
            spacing: _margins

            QGCButton {
                text:       qsTr("Clear")
                onClicked:  resetGraphs()
            }

            QGCButton {
                text:       dataTimer.running ? qsTr("Stop") : qsTr("Start")
375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398
                onClicked: {
                    dataTimer.running = !dataTimer.running
                    if (autoModeChange.checked) {
                        _activeVehicle.flightMode = dataTimer.running ? "Stabilized" : _activeVehicle.pauseFlightMode
                    }
                }
            }
        }

        QGCCheckBox {
            id:     autoModeChange
            text:   qsTr("Automatic Flight Mode Switching")
        }

        Column {
            visible: autoModeChange.checked
            QGCLabel {
                text:            qsTr("Switches to 'Stabilized' when you click Start.")
                font.pointSize:     ScreenTools.smallFontPointSize
            }

            QGCLabel {
                text:            qsTr("Switches to '%1' when you click Stop.").arg(_activeVehicle.pauseFlightMode)
                font.pointSize:     ScreenTools.smallFontPointSize
399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452
            }
        }
    }

    Column {
        Layout.fillWidth: true

        ChartView {
            anchors.left:       parent.left
            anchors.right:      parent.right
            height:             availableHeight / 2
            title:              _currentTuneType
            antialiasing:       true
            legend.alignment:   Qt.AlignRight

            LineSeries {
                id:         valueSeries
                name:       "Response"
                axisY:      valueYAxis
                axisX:      valueXAxis
            }

            LineSeries {
                id:         valueSetpointSeries
                name:       "Command"
                axisY:      valueYAxis
                axisX:      valueXAxis
            }
        }

        ChartView {
            anchors.left:       parent.left
            anchors.right:      parent.right
            height:             availableHeight / 2
            title:              _currentTuneType + qsTr(" Rate")
            antialiasing:       true
            legend.alignment:   Qt.AlignRight

            LineSeries {
                id:         valueRateSeries
                name:       "Response"
                axisY:      valueRateYAxis
                axisX:      valueRateXAxis
            }

            LineSeries {
                id:         valueRateSetpointSeries
                name:       "Command"
                axisY:      valueRateYAxis
                axisX:      valueRateXAxis
            }
        }
    }
} // RowLayout