From 20df7ebf6b64c1b04741f02b51fc7022fcf3aeca Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Wed, 27 May 2015 19:41:55 -0700 Subject: [PATCH] Convert RadioCal to Qml --- QGCApplication.pro | 13 +- qgroundcontrol.qrc | 7 +- src/AutoPilotPlugins/PX4/PowerComponent.cc | 1 - src/AutoPilotPlugins/PX4/RadioComponent.cc | 8 +- src/AutoPilotPlugins/PX4/RadioComponent.qml | 510 +++++++ .../PX4/RadioComponentController.cc} | 727 +++++----- .../PX4/RadioComponentController.h} | 157 ++- src/AutoPilotPlugins/PX4/SafetyComponent.cc | 1 - src/QGCApplication.cc | 2 + src/QmlControls/QGCView.qml | 8 +- src/ui/px4_configuration/PX4RCCalibration.ui | 1225 ----------------- src/ui/px4_configuration/RCValueWidget.cc | 306 ---- src/ui/px4_configuration/RCValueWidget.h | 111 -- 13 files changed, 962 insertions(+), 2114 deletions(-) create mode 100644 src/AutoPilotPlugins/PX4/RadioComponent.qml rename src/{ui/px4_configuration/PX4RCCalibration.cc => AutoPilotPlugins/PX4/RadioComponentController.cc} (53%) rename src/{ui/px4_configuration/PX4RCCalibration.h => AutoPilotPlugins/PX4/RadioComponentController.h} (64%) delete mode 100644 src/ui/px4_configuration/PX4RCCalibration.ui delete mode 100644 src/ui/px4_configuration/RCValueWidget.cc delete mode 100644 src/ui/px4_configuration/RCValueWidget.h diff --git a/QGCApplication.pro b/QGCApplication.pro index 67f34fca3..c9a05751c 100644 --- a/QGCApplication.pro +++ b/QGCApplication.pro @@ -184,7 +184,6 @@ FORMS += \ src/ui/mission/QGCMissionNavTakeoff.ui \ src/ui/mission/QGCMissionNavWaypoint.ui \ src/ui/mission/QGCMissionOther.ui \ - src/ui/px4_configuration/PX4RCCalibration.ui \ src/ui/QGCCommConfiguration.ui \ src/ui/QGCDataPlot2D.ui \ src/ui/QGCHilConfiguration.ui \ @@ -305,8 +304,6 @@ HEADERS += \ src/ui/mission/QGCMissionNavTakeoff.h \ src/ui/mission/QGCMissionNavWaypoint.h \ src/ui/mission/QGCMissionOther.h \ - src/ui/px4_configuration/PX4RCCalibration.h \ - src/ui/px4_configuration/RCValueWidget.h \ src/ui/QGCCommConfiguration.h \ src/ui/QGCDataPlot2D.h \ src/ui/QGCHilConfiguration.h \ @@ -431,8 +428,6 @@ SOURCES += \ src/ui/mission/QGCMissionNavTakeoff.cc \ src/ui/mission/QGCMissionNavWaypoint.cc \ src/ui/mission/QGCMissionOther.cc \ - src/ui/px4_configuration/PX4RCCalibration.cc \ - src/ui/px4_configuration/RCValueWidget.cc \ src/ui/QGCCommConfiguration.cc \ src/ui/QGCDataPlot2D.cc \ src/ui/QGCHilConfiguration.cc \ @@ -517,11 +512,12 @@ HEADERS += \ src/qgcunittest/MainWindowTest.h \ src/qgcunittest/MavlinkLogTest.h \ src/qgcunittest/MessageBoxTest.h \ - src/qgcunittest/PX4RCCalibrationTest.h \ src/qgcunittest/UnitTest.h \ src/VehicleSetup/SetupViewTest.h \ src/qgcunittest/FileManagerTest.h \ +#src/qgcunittest/PX4RCCalibrationTest.h \ + SOURCES += \ src/qgcunittest/FlightGearTest.cc \ src/qgcunittest/MultiSignalSpy.cc \ @@ -535,11 +531,12 @@ SOURCES += \ src/qgcunittest/MainWindowTest.cc \ src/qgcunittest/MavlinkLogTest.cc \ src/qgcunittest/MessageBoxTest.cc \ - src/qgcunittest/PX4RCCalibrationTest.cc \ src/qgcunittest/UnitTest.cc \ src/VehicleSetup/SetupViewTest.cc \ src/qgcunittest/FileManagerTest.cc \ +#src/qgcunittest/PX4RCCalibrationTest.cc \ + } # DebugBuild|WindowsDebugAndRelease } # AndroidBuild @@ -570,6 +567,7 @@ HEADERS+= \ src/AutoPilotPlugins/PX4/PX4Component.h \ src/AutoPilotPlugins/PX4/PX4ParameterLoader.h \ src/AutoPilotPlugins/PX4/RadioComponent.h \ + src/AutoPilotPlugins/PX4/RadioComponentController.h \ src/AutoPilotPlugins/PX4/SafetyComponent.h \ src/AutoPilotPlugins/PX4/SensorsComponent.h \ src/AutoPilotPlugins/PX4/SensorsComponentController.h \ @@ -599,6 +597,7 @@ SOURCES += \ src/AutoPilotPlugins/PX4/PX4Component.cc \ src/AutoPilotPlugins/PX4/PX4ParameterLoader.cc \ src/AutoPilotPlugins/PX4/RadioComponent.cc \ + src/AutoPilotPlugins/PX4/RadioComponentController.cc \ src/AutoPilotPlugins/PX4/SafetyComponent.cc \ src/AutoPilotPlugins/PX4/SensorsComponent.cc \ src/AutoPilotPlugins/PX4/SensorsComponentController.cc \ diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 8283130f4..02dee6604 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -50,6 +50,7 @@ src/VehicleSetup/FirmwareUpgrade.qml src/VehicleSetup/SetupParameterEditor.qml src/AutoPilotPlugins/PX4/SafetyComponent.qml + src/AutoPilotPlugins/PX4/RadioComponent.qml src/AutoPilotPlugins/PX4/PowerComponent.qml src/AutoPilotPlugins/PX4/SensorsComponent.qml src/AutoPilotPlugins/PX4/FlightModesComponent.qml @@ -220,7 +221,7 @@ - resources/calibration/accel_back.png + resources/calibration/accel_back.png resources/calibration/accel_front.png resources/calibration/accel_right.png resources/calibration/accel_down.png @@ -228,7 +229,7 @@ resources/calibration/accel_left.png - + resources/calibration/mode1/radioCenter.png resources/calibration/mode1/radioHome.png resources/calibration/mode1/radioRollLeft.png @@ -242,7 +243,7 @@ resources/calibration/mode1/radioSwitchMinMax.png - + resources/calibration/mode2/radioCenter.png resources/calibration/mode2/radioHome.png resources/calibration/mode2/radioRollLeft.png diff --git a/src/AutoPilotPlugins/PX4/PowerComponent.cc b/src/AutoPilotPlugins/PX4/PowerComponent.cc index 469f3dd0d..cb2f404b2 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponent.cc +++ b/src/AutoPilotPlugins/PX4/PowerComponent.cc @@ -25,7 +25,6 @@ /// @author Gus Grubba #include "PowerComponent.h" -#include "PX4RCCalibration.h" #include "QGCQmlWidgetHolder.h" #include "PX4AutoPilotPlugin.h" diff --git a/src/AutoPilotPlugins/PX4/RadioComponent.cc b/src/AutoPilotPlugins/PX4/RadioComponent.cc index ad6ecd240..5040baf70 100644 --- a/src/AutoPilotPlugins/PX4/RadioComponent.cc +++ b/src/AutoPilotPlugins/PX4/RadioComponent.cc @@ -25,7 +25,7 @@ /// @author Don Gagne #include "RadioComponent.h" -#include "PX4RCCalibration.h" +#include "QGCQmlWidgetHolder.h" #include "PX4AutoPilotPlugin.h" RadioComponent::RadioComponent(UASInterface* uas, AutoPilotPlugin* autopilot, QObject* parent) : @@ -140,7 +140,11 @@ QStringList RadioComponent::paramFilterList(void) const QWidget* RadioComponent::setupWidget(void) const { - return new PX4RCCalibration; + QGCQmlWidgetHolder* holder = new QGCQmlWidgetHolder(); + Q_CHECK_PTR(holder); + holder->setAutoPilot(_autopilot); + holder->setSource(QUrl::fromUserInput("qrc:/qml/RadioComponent.qml")); + return holder; } QUrl RadioComponent::summaryQmlSource(void) const diff --git a/src/AutoPilotPlugins/PX4/RadioComponent.qml b/src/AutoPilotPlugins/PX4/RadioComponent.qml new file mode 100644 index 000000000..509c23411 --- /dev/null +++ b/src/AutoPilotPlugins/PX4/RadioComponent.qml @@ -0,0 +1,510 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2015 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +/// @file +/// @brief Radio Calibration +/// @author Don Gagne + +import QtQuick 2.2 +import QtQuick.Controls 1.2 +import QtQuick.Dialogs 1.2 + +import QGroundControl.FactSystem 1.0 +import QGroundControl.FactControls 1.0 +import QGroundControl.Palette 1.0 +import QGroundControl.Controls 1.0 +import QGroundControl.ScreenTools 1.0 +import QGroundControl.Controllers 1.0 + +QGCView { + id: rootQGCView + viewComponent: view + + Component { + id: view + + QGCViewPanel { + id: viewPanel + + QGCPalette { id: qgcPal; colorGroupEnabled: enabled } + + readonly property real labelToMonitorMargin: defaultTextWidth * 3 + + function updateChannelCount() + { + if (controller.channelCount < controller.minChannelCount) { + showDialog(channelCountDialogComponent, "Radio Config", 50, 0) + } else { + hideDialog() + } + } + + RadioComponentController { + id: controller + factPanel: viewPanel + statusText: statusText + cancelButton: cancelButton + nextButton: nextButton + skipButton: skipButton + + onChannelCountChanged: updateChannelCount() + } + + Connections { + target: rootQGCView + + onCompleted: { + controller.start() + updateChannelCount() + } + } + + Component { + id: channelCountDialogComponent + + QGCViewMessage { + message: controller.channelCount == 0 ? "Please turn on transmitter." : controller.minChannelCount + " channels or more are needed to fly." + } + } + + Component { + id: spektrumBindDialogComponent + + QGCViewDialog { + + function accept() { + controller.spektrumBindMode(radioGroup.current.bindMode) + hideDialog() + } + + function reject() { + hideDialog() + } + + Column { + anchors.fill: parent + spacing: 5 + + QGCLabel { + width: parent.width + wrapMode: Text.WordWrap + text: "Click Ok to place your Spektrum receiver in the bind mode. Select the specific receiver type below:" + } + + ExclusiveGroup { id: radioGroup } + + QGCRadioButton { + exclusiveGroup: radioGroup + text: "DSM2 Mode" + + property int bindMode: RadioComponentController.DSM2 + } + + QGCRadioButton { + exclusiveGroup: radioGroup + text: "DSMX (7 channels or less)" + + property int bindMode: RadioComponentController.DSMX7 + } + + QGCRadioButton { + exclusiveGroup: radioGroup + checked: true + text: "DSMX (8 channels or more)" + + property int bindMode: RadioComponentController.DSMX8 + } + } + } + } // Component - spektrumBindDialogComponent + + // Live channel monitor control component + Component { + id: channelMonitorDisplayComponent + + Item { + property int rcValue: 1500 + + + property int __lastRcValue: 1500 + readonly property int __rcValueMaxJitter: 2 + property color __barColor: qgcPal.windowShade + + // Bar + Rectangle { + id: bar + anchors.verticalCenter: parent.verticalCenter + width: parent.width + height: parent.height / 2 + color: __barColor + } + + // Center point + Rectangle { + anchors.horizontalCenter: parent.horizontalCenter + width: defaultTextWidth / 2 + height: parent.height + color: qgcPal.window + } + + // Indicator + Rectangle { + anchors.verticalCenter: parent.verticalCenter + width: parent.height * 0.75 + height: width + x: ((Math.abs((rcValue - 1000) - (reversed ? 1000 : 0)) / 1000) * parent.width) - (width / 2) + radius: width / 2 + color: qgcPal.text + visible: mapped + } + + QGCLabel { + anchors.fill: parent + horizontalAlignment: Text.AlignHCenter + verticalAlignment: Text.AlignVCenter + text: "Not Mapped" + visible: !mapped + } + + ColorAnimation { + id: barAnimation + target: bar + property: "color" + from: "yellow" + to: __barColor + duration: 1500 + } + + onRcValueChanged: { + if (Math.abs(rcValue - __lastRcValue) > __rcValueMaxJitter) { + __lastRcValue = rcValue + barAnimation.restart() + } + } + + /* + // rcValue debugger + QGCLabel { + anchors.fill: parent + text: rcValue + } + */ + } + } // Component - channelMonitorDisplayComponent + + // Main view Qml starts here + + QGCLabel { + id: header + font.pointSize: ScreenTools.largeFontPointSize + text: "RADIO CONFIG" + } + + Item { + id: spacer + anchors.top: header.bottom + width: parent.width + height: 10 + } + + // Left side column + Column { + id: leftColumn + anchors.top: spacer.bottom + anchors.left: parent.left + anchors.right: columnSpacer.left + spacing: 10 + + Row { + spacing: 10 + + QGCLabel { + anchors.baseline: bindButton.baseline + text: "Place Spektrum satellite receiver in bind mode:" + } + + QGCButton { + id: bindButton + text: "Spektrum Bind" + + onClicked: showDialog(spektrumBindDialogComponent, "Radio Config", 50, StandardButton.Ok | StandardButton.Cancel) + } + } + + // Attitude Controls + Column { + width: parent.width + spacing: 5 + + QGCLabel { text: "Attitude Controls" } + + Item { + width: parent.width + height: defaultTextHeight * 2 + + QGCLabel { + id: rollLabel + width: defaultTextWidth * 10 + text: "Roll" + } + + Loader { + id: rollLoader + anchors.left: rollLabel.right + anchors.right: parent.right + height: rootQGCView.defaultTextHeight + width: 100 + sourceComponent: channelMonitorDisplayComponent + + property real defaultTextWidth: rootQGCView.defaultTextWidth + property bool mapped: controller.rollChannelMapped + property bool reversed: controller.rollChannelReversed + } + + Connections { + target: controller + + onRollChannelRCValueChanged: rollLoader.item.rcValue = rcValue + } + } + + Item { + width: parent.width + height: defaultTextHeight * 2 + + QGCLabel { + id: pitchLabel + width: defaultTextWidth * 10 + text: "Pitch" + } + + Loader { + id: pitchLoader + anchors.left: pitchLabel.right + anchors.right: parent.right + height: rootQGCView.defaultTextHeight + width: 100 + sourceComponent: channelMonitorDisplayComponent + + property real defaultTextWidth: rootQGCView.defaultTextWidth + property bool mapped: controller.pitchChannelMapped + property bool reversed: controller.pitchChannelReversed + } + + Connections { + target: controller + + onPitchChannelRCValueChanged: pitchLoader.item.rcValue = rcValue + } + } + + Item { + width: parent.width + height: defaultTextHeight * 2 + + QGCLabel { + id: yawLabel + width: defaultTextWidth * 10 + text: "Yaw" + } + + Loader { + id: yawLoader + anchors.left: yawLabel.right + anchors.right: parent.right + height: rootQGCView.defaultTextHeight + width: 100 + sourceComponent: channelMonitorDisplayComponent + + property real defaultTextWidth: rootQGCView.defaultTextWidth + property bool mapped: controller.yawChannelMapped + property bool reversed: controller.yawChannelReversed + } + + Connections { + target: controller + + onYawChannelRCValueChanged: yawLoader.item.rcValue = rcValue + } + } + + Item { + width: parent.width + height: defaultTextHeight * 2 + + QGCLabel { + id: throttleLabel + width: defaultTextWidth * 10 + text: "Throttle" + } + + Loader { + id: throttleLoader + anchors.left: throttleLabel.right + anchors.right: parent.right + height: rootQGCView.defaultTextHeight + width: 100 + sourceComponent: channelMonitorDisplayComponent + + property real defaultTextWidth: rootQGCView.defaultTextWidth + property bool mapped: controller.throttleChannelMapped + property bool reversed: controller.throttleChannelReversed + } + + Connections { + target: controller + + onThrottleChannelRCValueChanged: throttleLoader.item.rcValue = rcValue + } + } + } // Column - Attitude Control labels + + // Command Buttons + Row { + spacing: 10 + + QGCButton { + id: skipButton + text: "Skip" + + onClicked: controller.skipButtonClicked() + } + + QGCButton { + id: cancelButton + text: "Cancel" + + onClicked: controller.cancelButtonClicked() + } + + QGCButton { + id: nextButton + primary: true + text: "Calibrate" + + onClicked: controller.nextButtonClicked() + } + } // Row - Buttons + + // Status Text + QGCLabel { + id: statusText + width: parent.width + wrapMode: Text.WordWrap + } + } // Column - Left Column + + Item { + id: columnSpacer + anchors.right: rightColumn.left + width: 20 + } + + // Right side column + Column { + id: rightColumn + anchors.top: spacer.bottom + anchors.right: parent.right + width: defaultTextWidth * 35 + spacing: 10 + + Row { + spacing: 10 + ExclusiveGroup { id: modeGroup } + + QGCRadioButton { + exclusiveGroup: modeGroup + text: "Mode 1" + checked: controller.transmitterMode == 1 + + onClicked: controller.transmitterMode = 1 + } + + QGCRadioButton { + exclusiveGroup: modeGroup + text: "Mode 2" + checked: controller.transmitterMode == 2 + + onClicked: controller.transmitterMode = 2 + } + } + + Image { + width: parent.width + height: defaultTextHeight * 15 + fillMode: Image.PreserveAspectFit + smooth: true + source: controller.imageHelp + } + + // Channel monitor + Column { + width: parent.width + spacing: 5 + + QGCLabel { text: "Channel Monitor" } + + Connections { + target: controller + + onChannelRCValueChanged: { + if (channelMonitorRepeater.itemAt(channel)) { + channelMonitorRepeater.itemAt(channel).loader.item.rcValue = rcValue + } + } + } + + Repeater { + id: channelMonitorRepeater + model: controller.channelCount + width: parent.width + + Row { + spacing: 5 + + // Need this to get to loader from Connections above + property Item loader: theLoader + + QGCLabel { + id: channelLabel + text: modelData + 1 + } + + Loader { + id: theLoader + anchors.verticalCenter: channelLabel.verticalCenter + height: rootQGCView.defaultTextHeight + width: 200 + sourceComponent: channelMonitorDisplayComponent + + property real defaultTextWidth: rootQGCView.defaultTextWidth + property bool mapped: true + readonly property bool reversed: false + } + } + } + } // Column - Channel Monitor + } // Column - Right Column + } // QGCViewPanel + } // Component - view +} diff --git a/src/ui/px4_configuration/PX4RCCalibration.cc b/src/AutoPilotPlugins/PX4/RadioComponentController.cc similarity index 53% rename from src/ui/px4_configuration/PX4RCCalibration.cc rename to src/AutoPilotPlugins/PX4/RadioComponentController.cc index ac019ee0a..84d41826d 100644 --- a/src/ui/px4_configuration/PX4RCCalibration.cc +++ b/src/AutoPilotPlugins/PX4/RadioComponentController.cc @@ -2,7 +2,7 @@ QGroundControl Open Source Ground Control Station - (c) 2009, 2014 QGROUNDCONTROL PROJECT + (c) 2009, 2015 QGROUNDCONTROL PROJECT This file is part of the QGROUNDCONTROL project @@ -22,51 +22,51 @@ ======================================================================*/ /// @file -/// @brief PX4 RC Calibration Widget +/// @brief Radio Config Qml Controller /// @author Don Gagne - -#include "PX4RCCalibration.h" +#include "RadioComponentController.h" #include "UASManager.h" #include "QGCMessageBox.h" #include "AutoPilotPluginManager.h" -QGC_LOGGING_CATEGORY(PX4RCCalibrationLog, "PX4RCCalibrationLog") +#include + +QGC_LOGGING_CATEGORY(RadioComponentControllerLog, "RadioComponentControllerLog") -const int PX4RCCalibration::_updateInterval = 150; ///< Interval for timer which updates radio channel widgets -const int PX4RCCalibration::_rcCalPWMCenterPoint = ((PX4RCCalibration::_rcCalPWMValidMaxValue - PX4RCCalibration::_rcCalPWMValidMinValue) / 2.0f) + PX4RCCalibration::_rcCalPWMValidMinValue; +const int RadioComponentController::_updateInterval = 150; ///< Interval for timer which updates radio channel widgets +const int RadioComponentController::_rcCalPWMCenterPoint = ((RadioComponentController::_rcCalPWMValidMaxValue - RadioComponentController::_rcCalPWMValidMinValue) / 2.0f) + RadioComponentController::_rcCalPWMValidMinValue; // FIXME: Double check these mins againt 150% throws -const int PX4RCCalibration::_rcCalPWMValidMinValue = 1300; ///< Largest valid minimum PWM Min range value -const int PX4RCCalibration::_rcCalPWMValidMaxValue = 1700; ///< Smallest valid maximum PWM Max range value -const int PX4RCCalibration::_rcCalPWMDefaultMinValue = 1000; ///< Default value for Min if not set -const int PX4RCCalibration::_rcCalPWMDefaultMaxValue = 2000; ///< Default value for Max if not set -const int PX4RCCalibration::_rcCalRoughCenterDelta = 50; ///< Delta around center point which is considered to be roughly centered -const int PX4RCCalibration::_rcCalMoveDelta = 300; ///< Amount of delta past center which is considered stick movement -const int PX4RCCalibration::_rcCalSettleDelta = 20; ///< Amount of delta which is considered no stick movement -const int PX4RCCalibration::_rcCalMinDelta = 100; ///< Amount of delta allowed around min value to consider channel at min - -const int PX4RCCalibration::_stickDetectSettleMSecs = 500; - -const char* PX4RCCalibration::_imageFilePrefix = ":/res/calibration/"; -const char* PX4RCCalibration::_imageFileMode1Dir = "mode1/"; -const char* PX4RCCalibration::_imageFileMode2Dir = "mode2/"; -const char* PX4RCCalibration::_imageCenter = "radioCenter.png"; -const char* PX4RCCalibration::_imageHome = "radioHome.png"; -const char* PX4RCCalibration::_imageThrottleUp = "radioThrottleUp.png"; -const char* PX4RCCalibration::_imageThrottleDown = "radioThrottleDown.png"; -const char* PX4RCCalibration::_imageYawLeft = "radioYawLeft.png"; -const char* PX4RCCalibration::_imageYawRight = "radioYawRight"; -const char* PX4RCCalibration::_imageRollLeft = "radioRollLeft.png"; -const char* PX4RCCalibration::_imageRollRight = "radioRollRight.png"; -const char* PX4RCCalibration::_imagePitchUp = "radioPitchUp"; -const char* PX4RCCalibration::_imagePitchDown = "radioPitchDown"; -const char* PX4RCCalibration::_imageSwitchMinMax = "radioSwitchMinMax"; - -const char* PX4RCCalibration::_settingsGroup = "RadioCalibration"; -const char* PX4RCCalibration::_settingsKeyTransmitterMode = "TransmitterMode"; - -const struct PX4RCCalibration::FunctionInfo PX4RCCalibration::_rgFunctionInfo[PX4RCCalibration::rcCalFunctionMax] = { +const int RadioComponentController::_rcCalPWMValidMinValue = 1300; ///< Largest valid minimum PWM Min range value +const int RadioComponentController::_rcCalPWMValidMaxValue = 1700; ///< Smallest valid maximum PWM Max range value +const int RadioComponentController::_rcCalPWMDefaultMinValue = 1000; ///< Default value for Min if not set +const int RadioComponentController::_rcCalPWMDefaultMaxValue = 2000; ///< Default value for Max if not set +const int RadioComponentController::_rcCalRoughCenterDelta = 50; ///< Delta around center point which is considered to be roughly centered +const int RadioComponentController::_rcCalMoveDelta = 300; ///< Amount of delta past center which is considered stick movement +const int RadioComponentController::_rcCalSettleDelta = 20; ///< Amount of delta which is considered no stick movement +const int RadioComponentController::_rcCalMinDelta = 100; ///< Amount of delta allowed around min value to consider channel at min + +const int RadioComponentController::_stickDetectSettleMSecs = 500; + +const char* RadioComponentController::_imageFilePrefix = "calibration/"; +const char* RadioComponentController::_imageFileMode1Dir = "mode1/"; +const char* RadioComponentController::_imageFileMode2Dir = "mode2/"; +const char* RadioComponentController::_imageCenter = "radioCenter.png"; +const char* RadioComponentController::_imageHome = "radioHome.png"; +const char* RadioComponentController::_imageThrottleUp = "radioThrottleUp.png"; +const char* RadioComponentController::_imageThrottleDown = "radioThrottleDown.png"; +const char* RadioComponentController::_imageYawLeft = "radioYawLeft.png"; +const char* RadioComponentController::_imageYawRight = "radioYawRight.png"; +const char* RadioComponentController::_imageRollLeft = "radioRollLeft.png"; +const char* RadioComponentController::_imageRollRight = "radioRollRight.png"; +const char* RadioComponentController::_imagePitchUp = "radioPitchUp.png"; +const char* RadioComponentController::_imagePitchDown = "radioPitchDown.png"; +const char* RadioComponentController::_imageSwitchMinMax = "radioSwitchMinMax.png"; + +const char* RadioComponentController::_settingsGroup = "RadioCalibration"; +const char* RadioComponentController::_settingsKeyTransmitterMode = "TransmitterMode"; + +const struct RadioComponentController::FunctionInfo RadioComponentController::_rgFunctionInfo[RadioComponentController::rcCalFunctionMax] = { //Parameter required { "RC_MAP_ROLL" }, { "RC_MAP_PITCH" }, @@ -82,103 +82,36 @@ const struct PX4RCCalibration::FunctionInfo PX4RCCalibration::_rgFunctionInfo[PX { "RC_MAP_AUX2" }, }; -PX4RCCalibration::PX4RCCalibration(QWidget *parent) : - QWidget(parent), +RadioComponentController::RadioComponentController(void) : _currentStep(-1), _transmitterMode(2), _chanCount(0), _rcCalState(rcCalStateChannelWait), - _uas(NULL), - _ui(new Ui::PX4RCCalibration), - _unitTestMode(false) + _unitTestMode(false), + _statusText(NULL), + _cancelButton(NULL), + _nextButton(NULL), + _skipButton(NULL) { - _ui->setupUi(this); - - // Initialize arrays of monitor control pointers. This allows for more efficient code writing using "for" loops. - for (int chan=0; chan<_chanMax; chan++) { - QString radioWidgetName; - - radioWidgetName = "channel%1Value"; - RCValueWidget* monitorWidget = findChild(radioWidgetName.arg(chan+1)); - Q_ASSERT(monitorWidget); - _rgRCValueMonitorWidget[chan] = monitorWidget; - monitorWidget->setSmallMode(); // Monitor display uses small display - - radioWidgetName = "channel%1Label"; - QLabel* monitorLabel = findChild(radioWidgetName.arg(chan+1)); - Q_ASSERT(monitorLabel); - _rgRCValueMonitorLabel[chan] = monitorLabel; - } - - // Initialize array of attitude controls. Order here doesn't matter. - _rgAttitudeControl[0].function = rcCalFunctionThrottle; - _rgAttitudeControl[0].valueWidget = _ui->throttleValue; - _rgAttitudeControl[1].function = rcCalFunctionYaw; - _rgAttitudeControl[1].valueWidget = _ui->yawValue; - _rgAttitudeControl[2].function = rcCalFunctionRoll; - _rgAttitudeControl[2].valueWidget = _ui->rollValue; - _rgAttitudeControl[3].function = rcCalFunctionPitch; - _rgAttitudeControl[3].valueWidget = _ui->pitchValue; - _rgAttitudeControl[4].function = rcCalFunctionFlaps; - _rgAttitudeControl[4].valueWidget = _ui->flapsValue; - - // This code assume we already have an active UAS with ready parameters - _uas = UASManager::instance()->getActiveUAS(); - Q_ASSERT(_uas); - - // Connect new signals - - bool fSucceeded; - Q_UNUSED(fSucceeded); - fSucceeded = connect(_uas, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(_remoteControlChannelRawChanged(int,float))); - Q_ASSERT(fSucceeded); - - _autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uas); - Q_ASSERT(_autopilot); - Q_ASSERT(_autopilot->pluginReady()); - - connect(_ui->spektrumBind, &QPushButton::clicked, this, &PX4RCCalibration::_spektrumBind); - - _updateTimer.setInterval(150); - _updateTimer.start(); - - connect(_ui->rcCalCancel, &QPushButton::clicked, this, &PX4RCCalibration::_stopCalibration); - connect(_ui->rcCalSkip, &QPushButton::clicked, this, &PX4RCCalibration::_skipButton); - connect(_ui->rcCalNext, &QPushButton::clicked, this, &PX4RCCalibration::_nextButton); - - connect(_ui->rollTrim, &QPushButton::clicked, this, &PX4RCCalibration::_trimNYI); - connect(_ui->yawTrim, &QPushButton::clicked, this, &PX4RCCalibration::_trimNYI); - connect(_ui->pitchTrim, &QPushButton::clicked, this, &PX4RCCalibration::_trimNYI); - connect(_ui->throttleTrim, &QPushButton::clicked, this, &PX4RCCalibration::_trimNYI); - + connect(_uas, &UASInterface::remoteControlChannelRawChanged, this, &RadioComponentController::_remoteControlChannelRawChanged); _loadSettings(); - - if (_transmitterMode == 1) { - _ui->mode1->setChecked(true); - _mode1Toggled(true); - } else if (_transmitterMode == 2) { - _ui->mode2->setChecked(true); - _mode2Toggled(true); - } else { - Q_ASSERT(false); - } - - connect(_ui->mode1, &QAbstractButton::toggled, this, &PX4RCCalibration::_mode1Toggled); - connect(_ui->mode2, &QAbstractButton::toggled, this, &PX4RCCalibration::_mode2Toggled); + _resetInternalCalibrationValues(); +} + +void RadioComponentController::start(void) +{ _stopCalibration(); - - connect(&_updateTimer, &QTimer::timeout, this, &PX4RCCalibration::_updateView); _setInternalCalibrationValuesFromParameters(); } -PX4RCCalibration::~PX4RCCalibration() +RadioComponentController::~RadioComponentController() { _storeSettings(); } /// @brief Returns the state machine entry for the specified state. -const PX4RCCalibration::stateMachineEntry* PX4RCCalibration::_getStateMachineEntry(int step) +const RadioComponentController::stateMachineEntry* RadioComponentController::_getStateMachineEntry(int step) { static const char* msgBegin = "Lower the Throttle stick all the way down as shown in diagram.\nReset all transmitter trims to center.\n\n" "It is recommended to disconnect all motors for additional safety, however, the system is designed to not arm during the calibration.\n\n" @@ -206,22 +139,22 @@ const PX4RCCalibration::stateMachineEntry* PX4RCCalibration::_getStateMachineEnt static const stateMachineEntry rgStateMachine[] = { //Function - { rcCalFunctionMax, msgBegin, _imageHome, &PX4RCCalibration::_inputCenterWaitBegin, &PX4RCCalibration::_saveAllTrims, NULL }, - { rcCalFunctionThrottle, msgThrottleUp, _imageThrottleUp, &PX4RCCalibration::_inputStickDetect, NULL, NULL }, - { rcCalFunctionThrottle, msgThrottleDown, _imageThrottleDown, &PX4RCCalibration::_inputStickMin, NULL, NULL }, - { rcCalFunctionYaw, msgYawRight, _imageYawRight, &PX4RCCalibration::_inputStickDetect, NULL, NULL }, - { rcCalFunctionYaw, msgYawLeft, _imageYawLeft, &PX4RCCalibration::_inputStickMin, NULL, NULL }, - { rcCalFunctionRoll, msgRollRight, _imageRollRight, &PX4RCCalibration::_inputStickDetect, NULL, NULL }, - { rcCalFunctionRoll, msgRollLeft, _imageRollLeft, &PX4RCCalibration::_inputStickMin, NULL, NULL }, - { rcCalFunctionPitch, msgPitchUp, _imagePitchUp, &PX4RCCalibration::_inputStickDetect, NULL, NULL }, - { rcCalFunctionPitch, msgPitchDown, _imagePitchDown, &PX4RCCalibration::_inputStickMin, NULL, NULL }, - { rcCalFunctionPitch, msgPitchCenter, _imageHome, &PX4RCCalibration::_inputCenterWait, NULL, NULL }, - { rcCalFunctionMax, msgSwitchMinMax, _imageSwitchMinMax, &PX4RCCalibration::_inputSwitchMinMax, &PX4RCCalibration::_nextStep, NULL }, - { rcCalFunctionFlaps, msgFlapsDetect, _imageThrottleDown, &PX4RCCalibration::_inputFlapsDetect, &PX4RCCalibration::_saveFlapsDown, &PX4RCCalibration::_skipFlaps }, - { rcCalFunctionFlaps, msgFlapsUp, _imageThrottleDown, &PX4RCCalibration::_inputFlapsUp, NULL, NULL }, - { rcCalFunctionAux1, msgAux1Switch, _imageThrottleDown, &PX4RCCalibration::_inputSwitchDetect, NULL, &PX4RCCalibration::_nextStep }, - { rcCalFunctionAux2, msgAux2Switch, _imageThrottleDown, &PX4RCCalibration::_inputSwitchDetect, NULL, &PX4RCCalibration::_nextStep }, - { rcCalFunctionMax, msgComplete, _imageThrottleDown, NULL, &PX4RCCalibration::_writeCalibration, NULL }, + { rcCalFunctionMax, msgBegin, _imageHome, &RadioComponentController::_inputCenterWaitBegin, &RadioComponentController::_saveAllTrims, NULL }, + { rcCalFunctionThrottle, msgThrottleUp, _imageThrottleUp, &RadioComponentController::_inputStickDetect, NULL, NULL }, + { rcCalFunctionThrottle, msgThrottleDown, _imageThrottleDown, &RadioComponentController::_inputStickMin, NULL, NULL }, + { rcCalFunctionYaw, msgYawRight, _imageYawRight, &RadioComponentController::_inputStickDetect, NULL, NULL }, + { rcCalFunctionYaw, msgYawLeft, _imageYawLeft, &RadioComponentController::_inputStickMin, NULL, NULL }, + { rcCalFunctionRoll, msgRollRight, _imageRollRight, &RadioComponentController::_inputStickDetect, NULL, NULL }, + { rcCalFunctionRoll, msgRollLeft, _imageRollLeft, &RadioComponentController::_inputStickMin, NULL, NULL }, + { rcCalFunctionPitch, msgPitchUp, _imagePitchUp, &RadioComponentController::_inputStickDetect, NULL, NULL }, + { rcCalFunctionPitch, msgPitchDown, _imagePitchDown, &RadioComponentController::_inputStickMin, NULL, NULL }, + { rcCalFunctionPitch, msgPitchCenter, _imageHome, &RadioComponentController::_inputCenterWait, NULL, NULL }, + { rcCalFunctionMax, msgSwitchMinMax, _imageSwitchMinMax, &RadioComponentController::_inputSwitchMinMax, &RadioComponentController::_advanceState, NULL }, + { rcCalFunctionFlaps, msgFlapsDetect, _imageThrottleDown, &RadioComponentController::_inputFlapsDetect, &RadioComponentController::_saveFlapsDown, &RadioComponentController::_skipFlaps }, + { rcCalFunctionFlaps, msgFlapsUp, _imageThrottleDown, &RadioComponentController::_inputFlapsUp, NULL, NULL }, + { rcCalFunctionAux1, msgAux1Switch, _imageThrottleDown, &RadioComponentController::_inputSwitchDetect, NULL, &RadioComponentController::_advanceState }, + { rcCalFunctionAux2, msgAux2Switch, _imageThrottleDown, &RadioComponentController::_inputSwitchDetect, NULL, &RadioComponentController::_advanceState }, + { rcCalFunctionMax, msgComplete, _imageThrottleDown, NULL, &RadioComponentController::_writeCalibration, NULL }, }; Q_ASSERT(step >=0 && step < (int)(sizeof(rgStateMachine) / sizeof(rgStateMachine[0]))); @@ -229,7 +162,7 @@ const PX4RCCalibration::stateMachineEntry* PX4RCCalibration::_getStateMachineEnt return &rgStateMachine[step]; } -void PX4RCCalibration::_nextStep(void) +void RadioComponentController::_advanceState(void) { _currentStep++; _setupCurrentState(); @@ -237,11 +170,11 @@ void PX4RCCalibration::_nextStep(void) /// @brief Sets up the state machine according to the current step from _currentStep. -void PX4RCCalibration::_setupCurrentState(void) +void RadioComponentController::_setupCurrentState(void) { const stateMachineEntry* state = _getStateMachineEntry(_currentStep); - _ui->rcCalStatus->setText(state->instructions); + _statusText->setProperty("text", state->instructions); _setHelpImage(state->image); @@ -250,46 +183,63 @@ void PX4RCCalibration::_setupCurrentState(void) _rcCalSaveCurrentValues(); - _ui->rcCalNext->setEnabled(state->nextFn != NULL); - _ui->rcCalSkip->setEnabled(state->skipFn != NULL); + _nextButton->setEnabled(state->nextFn != NULL); + _skipButton->setEnabled(state->skipFn != NULL); } /// @brief This routine is called whenever a raw value for an RC channel changes. It will call the input /// function as specified by the state machine. /// @param chan RC channel on which signal is coming from (0-based) /// @param fval Current value for channel -void PX4RCCalibration::_remoteControlChannelRawChanged(int chan, float fval) +void RadioComponentController::_remoteControlChannelRawChanged(int chan, float fval) { - Q_ASSERT(chan >= 0 && chan <= _chanMax); - - // We always update raw values - _rcRawValue[chan] = fval; - - qCDebug(PX4RCCalibrationLog) << "Raw value" << chan << fval; - - if (_currentStep == -1) { - // Track the receiver channel count by keeping track of how many channels we see - if (chan + 1 > (int)_chanCount) { - _chanCount = chan + 1; - _ui->receiverInfo->setText(tr("%1 channel receiver").arg(_chanCount)); - if (_chanCount < _chanMinimum) { - _ui->rcCalStatus->setText(tr("Detected %1 radio channels. To operate PX4, you need at least %2 channels.").arg(_chanCount).arg(_chanMinimum)); - } else { - _ui->rcCalStatus->clear(); + if (chan >= 0 && chan <= _chanMax) { + // We always update raw values + _rcRawValue[chan] = fval; + emit channelRCValueChanged(chan, _rcRawValue[chan]); + + // Signal attitude rc values to Qml if mapped + if (_rgChannelInfo[chan].function != rcCalFunctionMax) { + switch (_rgChannelInfo[chan].function) { + case rcCalFunctionRoll: + emit rollChannelRCValueChanged(_rcRawValue[chan]); + break; + case rcCalFunctionPitch: + emit pitchChannelRCValueChanged(_rcRawValue[chan]); + break; + case rcCalFunctionYaw: + emit yawChannelRCValueChanged(_rcRawValue[chan]); + break; + case rcCalFunctionThrottle: + emit throttleChannelRCValueChanged(_rcRawValue[chan]); + break; + default: + break; + } } - } - - if (_currentStep != -1) { - const stateMachineEntry* state = _getStateMachineEntry(_currentStep); - Q_ASSERT(state); - if (state->rcInputFn) { - (this->*state->rcInputFn)(state->function, chan, fval); + + qCDebug(RadioComponentControllerLog) << "Raw value" << chan << fval; + + if (_currentStep == -1) { + // Track the receiver channel count by keeping track of how many channels we see + if (chan + 1 > (int)_chanCount) { + _chanCount = chan + 1; + emit channelCountChanged(_chanCount); + } + } + + if (_currentStep != -1) { + const stateMachineEntry* state = _getStateMachineEntry(_currentStep); + Q_ASSERT(state); + if (state->rcInputFn) { + (this->*state->rcInputFn)(state->function, chan, fval); + } } } } -void PX4RCCalibration::_nextButton(void) +void RadioComponentController::nextButtonClicked(void) { if (_currentStep == -1) { // Need to have enough channels @@ -310,7 +260,7 @@ void PX4RCCalibration::_nextButton(void) } } -void PX4RCCalibration::_skipButton(void) +void RadioComponentController::skipButtonClicked(void) { Q_ASSERT(_currentStep != -1); @@ -320,12 +270,12 @@ void PX4RCCalibration::_skipButton(void) (this->*state->skipFn)(); } -void PX4RCCalibration::_trimNYI(void) +void RadioComponentController::cancelButtonClicked(void) { - QGCMessageBox::warning(tr("Set Trim"), tr("Setting individual trims is not yet implemented. You will need to go through full calibration to set trims.")); + _stopCalibration(); } -void PX4RCCalibration::_saveAllTrims(void) +void RadioComponentController::_saveAllTrims(void) { // We save all trims as the first step. At this point no channels are mapped but it should still // allow us to get good trims for the roll/pitch/yaw/throttle even though we don't know which @@ -333,14 +283,14 @@ void PX4RCCalibration::_saveAllTrims(void) // trims reset to correct values. for (int i=0; i<_chanCount; i++) { - qCDebug(PX4RCCalibrationLog) << "_saveAllTrims trim" << _rcRawValue[i]; + qCDebug(RadioComponentControllerLog) << "_saveAllTrims trim" << _rcRawValue[i]; _rgChannelInfo[i].rcTrim = _rcRawValue[i]; } - _nextStep(); + _advanceState(); } /// @brief Waits for the sticks to be centered, enabling Next when done. -void PX4RCCalibration::_inputCenterWaitBegin(enum rcCalFunctions function, int chan, int value) +void RadioComponentController::_inputCenterWaitBegin(enum rcCalFunctions function, int chan, int value) { Q_UNUSED(function); Q_UNUSED(chan); @@ -348,17 +298,17 @@ void PX4RCCalibration::_inputCenterWaitBegin(enum rcCalFunctions function, int c // FIXME: Doesn't wait for center - _ui->rcCalNext->setEnabled(true); + _nextButton->setEnabled(true); } -bool PX4RCCalibration::_stickSettleComplete(int value) +bool RadioComponentController::_stickSettleComplete(int value) { // We are waiting for the stick to settle out to a max position if (abs(_stickDetectValue - value) > _rcCalSettleDelta) { // Stick is moving too much to consider stopped - qCDebug(PX4RCCalibrationLog) << "_stickSettleComplete still moving, _stickDetectValue:value" << _stickDetectValue << value; + qCDebug(RadioComponentControllerLog) << "_stickSettleComplete still moving, _stickDetectValue:value" << _stickDetectValue << value; _stickDetectValue = value; _stickDetectSettleStarted = false; @@ -375,7 +325,7 @@ bool PX4RCCalibration::_stickSettleComplete(int value) } else { // Start waiting for the stick to stay settled for _stickDetectSettleWaitMSecs msecs - qCDebug(PX4RCCalibrationLog) << "_stickSettleComplete starting settle timer, _stickDetectValue:value" << _stickDetectValue << value; + qCDebug(RadioComponentControllerLog) << "_stickSettleComplete starting settle timer, _stickDetectValue:value" << _stickDetectValue << value; _stickDetectSettleStarted = true; _stickDetectSettleElapsed.start(); @@ -385,9 +335,9 @@ bool PX4RCCalibration::_stickSettleComplete(int value) return false; } -void PX4RCCalibration::_inputStickDetect(enum rcCalFunctions function, int channel, int value) +void RadioComponentController::_inputStickDetect(enum rcCalFunctions function, int channel, int value) { - qCDebug(PX4RCCalibrationLog) << "_inputStickDetect function:channel:value" << _rgFunctionInfo[function].parameterName << channel << value; + qCDebug(RadioComponentControllerLog) << "_inputStickDetect function:channel:value" << _rgFunctionInfo[function].parameterName << channel << value; // If this channel is already used in a mapping we can't use it again if (_rgChannelInfo[channel].function != rcCalFunctionMax) { @@ -400,7 +350,7 @@ void PX4RCCalibration::_inputStickDetect(enum rcCalFunctions function, int chann if (abs(_rcValueSave[channel] - value) > _rcCalMoveDelta) { // Stick has moved far enough to consider it as being selected for the function - qCDebug(PX4RCCalibrationLog) << "_inputStickDetect starting settle wait, function:channel:value" << function << channel << value; + qCDebug(RadioComponentControllerLog) << "_inputStickDetect starting settle wait, function:channel:value" << function << channel << value; // Setup up to detect stick being pegged to min or max value _stickDetectChannel = channel; @@ -411,7 +361,7 @@ void PX4RCCalibration::_inputStickDetect(enum rcCalFunctions function, int chann if (_stickSettleComplete(value)) { ChannelInfo* info = &_rgChannelInfo[channel]; - qCDebug(PX4RCCalibrationLog) << "_inputStickDetect settle complete, function:channel:value" << function << channel << value; + qCDebug(RadioComponentControllerLog) << "_inputStickDetect settle complete, function:channel:value" << function << channel << value; // Stick detection is complete. Stick should be at max position. // Map the channel to the function @@ -422,21 +372,19 @@ void PX4RCCalibration::_inputStickDetect(enum rcCalFunctions function, int chann info->reversed = value < _rcValueSave[channel]; if (info->reversed) { - _rgRCValueMonitorWidget[channel]->setMin(value); - _rgRCValueMonitorWidget[channel]->setMinValid(true); _rgChannelInfo[channel].rcMin = value; } else { - _rgRCValueMonitorWidget[channel]->setMax(value); - _rgRCValueMonitorWidget[channel]->setMaxValid(true); _rgChannelInfo[channel].rcMax = value; } - _nextStep(); + _signalAllAttiudeValueChanges(); + + _advanceState(); } } } -void PX4RCCalibration::_inputStickMin(enum rcCalFunctions function, int channel, int value) +void RadioComponentController::_inputStickMin(enum rcCalFunctions function, int channel, int value) { // We only care about the channel mapped to the function we are working on if (_rgFunctionChannelMapping[function] != channel) { @@ -466,21 +414,17 @@ void PX4RCCalibration::_inputStickMin(enum rcCalFunctions function, int channel, // Stick detection is complete. Stick should be at min position. if (info->reversed) { - _rgRCValueMonitorWidget[channel]->setMax(value); - _rgRCValueMonitorWidget[channel]->setMaxValid(true); _rgChannelInfo[channel].rcMax = value; } else { - _rgRCValueMonitorWidget[channel]->setMin(value); - _rgRCValueMonitorWidget[channel]->setMinValid(true); _rgChannelInfo[channel].rcMin = value; } - _nextStep(); + _advanceState(); } } } -void PX4RCCalibration::_inputCenterWait(enum rcCalFunctions function, int channel, int value) +void RadioComponentController::_inputCenterWait(enum rcCalFunctions function, int channel, int value) { // We only care about the channel mapped to the function we are working on if (_rgFunctionChannelMapping[function] != channel) { @@ -498,13 +442,13 @@ void PX4RCCalibration::_inputCenterWait(enum rcCalFunctions function, int channe } } else { if (_stickSettleComplete(value)) { - _nextStep(); + _advanceState(); } } } /// @brief Saves min/max for non-mapped channels -void PX4RCCalibration::_inputSwitchMinMax(enum rcCalFunctions function, int channel, int value) +void RadioComponentController::_inputSwitchMinMax(enum rcCalFunctions function, int channel, int value) { Q_UNUSED(function); @@ -518,39 +462,35 @@ void PX4RCCalibration::_inputSwitchMinMax(enum rcCalFunctions function, int chan if (value < _rcCalPWMCenterPoint) { int minValue = qMin(_rgChannelInfo[channel].rcMin, value); - qCDebug(PX4RCCalibrationLog) << "_inputSwitchMinMax setting min channel:min" << channel << minValue; + qCDebug(RadioComponentControllerLog) << "_inputSwitchMinMax setting min channel:min" << channel << minValue; _rgChannelInfo[channel].rcMin = minValue; - _rgRCValueMonitorWidget[channel]->setMin(minValue); - _rgRCValueMonitorWidget[channel]->setMinValid(true); } else { int maxValue = qMax(_rgChannelInfo[channel].rcMax, value); - qCDebug(PX4RCCalibrationLog) << "_inputSwitchMinMax setting max channel:max" << channel << maxValue; + qCDebug(RadioComponentControllerLog) << "_inputSwitchMinMax setting max channel:max" << channel << maxValue; _rgChannelInfo[channel].rcMax = maxValue; - _rgRCValueMonitorWidget[channel]->setMax(maxValue); - _rgRCValueMonitorWidget[channel]->setMaxValid(true); } } } -void PX4RCCalibration::_skipFlaps(void) +void RadioComponentController::_skipFlaps(void) { // Flaps channel may have been identified. Clear it out. for (int i=0; i<_chanCount; i++) { - if (_rgChannelInfo[i].function == PX4RCCalibration::rcCalFunctionFlaps) { + if (_rgChannelInfo[i].function == RadioComponentController::rcCalFunctionFlaps) { _rgChannelInfo[i].function = rcCalFunctionMax; } } - _rgFunctionChannelMapping[PX4RCCalibration::rcCalFunctionFlaps] = _chanMax; + _rgFunctionChannelMapping[RadioComponentController::rcCalFunctionFlaps] = _chanMax; // Skip over flap steps _currentStep += 2; _setupCurrentState(); } -void PX4RCCalibration::_saveFlapsDown(void) +void RadioComponentController::_saveFlapsDown(void) { int channel = _rgFunctionChannelMapping[rcCalFunctionFlaps]; @@ -575,19 +515,15 @@ void PX4RCCalibration::_saveFlapsDown(void) info->reversed = rcValue < _rcValueSave[channel]; if (info->reversed) { - _rgRCValueMonitorWidget[channel]->setMin(rcValue); - _rgRCValueMonitorWidget[channel]->setMinValid(true); _rgChannelInfo[channel].rcMin = rcValue; } else { - _rgRCValueMonitorWidget[channel]->setMax(rcValue); - _rgRCValueMonitorWidget[channel]->setMaxValid(true); _rgChannelInfo[channel].rcMax = rcValue; } - _nextStep(); + _advanceState(); } -void PX4RCCalibration::_inputFlapsUp(enum rcCalFunctions function, int channel, int value) +void RadioComponentController::_inputFlapsUp(enum rcCalFunctions function, int channel, int value) { Q_UNUSED(function); @@ -623,21 +559,17 @@ void PX4RCCalibration::_inputFlapsUp(enum rcCalFunctions function, int channel, // Stick detection is complete. Stick should be at min position. if (info->reversed) { - _rgRCValueMonitorWidget[channel]->setMax(value); - _rgRCValueMonitorWidget[channel]->setMaxValid(true); _rgChannelInfo[channel].rcMax = value; } else { - _rgRCValueMonitorWidget[channel]->setMin(value); - _rgRCValueMonitorWidget[channel]->setMinValid(true); _rgChannelInfo[channel].rcMin = value; } - _nextStep(); + _advanceState(); } } } -void PX4RCCalibration::_switchDetect(enum rcCalFunctions function, int channel, int value, bool moveToNextStep) +void RadioComponentController::_switchDetect(enum rcCalFunctions function, int channel, int value, bool moveToNextStep) { // If this channel is already used in a mapping we can't use it again if (_rgChannelInfo[channel].function != rcCalFunctionMax) { @@ -654,35 +586,35 @@ void PX4RCCalibration::_switchDetect(enum rcCalFunctions function, int channel, _rgFunctionChannelMapping[function] = channel; info->function = function; - qCDebug(PX4RCCalibrationLog) << "Function:" << function << "mapped to:" << channel; + qCDebug(RadioComponentControllerLog) << "Function:" << function << "mapped to:" << channel; if (moveToNextStep) { - _nextStep(); + _advanceState(); } } } -void PX4RCCalibration::_inputSwitchDetect(enum rcCalFunctions function, int channel, int value) +void RadioComponentController::_inputSwitchDetect(enum rcCalFunctions function, int channel, int value) { _switchDetect(function, channel, value, true /* move to next step after detection */); } -void PX4RCCalibration::_inputFlapsDetect(enum rcCalFunctions function, int channel, int value) +void RadioComponentController::_inputFlapsDetect(enum rcCalFunctions function, int channel, int value) { _switchDetect(function, channel, value, false /* do not move to next step after detection */); } /// @brief Resets internal calibration values to their initial state in preparation for a new calibration sequence. -void PX4RCCalibration::_resetInternalCalibrationValues(void) +void RadioComponentController::_resetInternalCalibrationValues(void) { // Set all raw channels to not reversed and center point values for (size_t i=0; i<_chanMax; i++) { struct ChannelInfo* info = &_rgChannelInfo[i]; info->function = rcCalFunctionMax; info->reversed = false; - info->rcMin = PX4RCCalibration::_rcCalPWMCenterPoint; - info->rcMax = PX4RCCalibration::_rcCalPWMCenterPoint; - info->rcTrim = PX4RCCalibration::_rcCalPWMCenterPoint; + info->rcMin = RadioComponentController::_rcCalPWMCenterPoint; + info->rcMax = RadioComponentController::_rcCalPWMCenterPoint; + info->rcTrim = RadioComponentController::_rcCalPWMCenterPoint; } // Initialize attitude function mapping to function channel not set @@ -690,9 +622,6 @@ void PX4RCCalibration::_resetInternalCalibrationValues(void) _rgFunctionChannelMapping[i] = _chanMax; } - _showMinMaxOnRadioWidgets(false); - _showTrimOnRadioWidgets(false); - // Reserve the existing Flight Mode switch settings channels so we don't re-use them static const rcCalFunctions rgFlightModeFunctions[] = { @@ -707,22 +636,24 @@ void PX4RCCalibration::_resetInternalCalibrationValues(void) enum rcCalFunctions curFunction = rgFlightModeFunctions[i]; bool ok; - int switchChannel = _autopilot->getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[curFunction].parameterName)->value().toInt(&ok); + int switchChannel = getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[curFunction].parameterName)->value().toInt(&ok); Q_ASSERT(ok); // Parameter: 1-based channel, 0=not mapped // _rgFunctionChannelMapping: 0-based channel, _chanMax=not mapped if (switchChannel != 0) { - qCDebug(PX4RCCalibrationLog) << "Reserving 0-based switch channel" << switchChannel - 1; + qCDebug(RadioComponentControllerLog) << "Reserving 0-based switch channel" << switchChannel - 1; _rgFunctionChannelMapping[curFunction] = switchChannel - 1; _rgChannelInfo[switchChannel - 1].function = curFunction; } } + + _signalAllAttiudeValueChanges(); } /// @brief Sets internal calibration values from the stored parameters -void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void) +void RadioComponentController::_setInternalCalibrationValuesFromParameters(void) { // Initialize all function mappings to not set @@ -735,8 +666,6 @@ void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void) _rgFunctionChannelMapping[i] = _chanMax; } - // FIXME: Hardwired component id - // Pull parameters and update QString minTpl("RC%1_MIN"); @@ -749,16 +678,16 @@ void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void) for (int i = 0; i < _chanMax; ++i) { struct ChannelInfo* info = &_rgChannelInfo[i]; - info->rcTrim = _autopilot->getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1))->value().toInt(&convertOk); + info->rcTrim = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1))->value().toInt(&convertOk); Q_ASSERT(convertOk); - info->rcMin = _autopilot->getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1))->value().toInt(&convertOk); + info->rcMin = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1))->value().toInt(&convertOk); Q_ASSERT(convertOk); - info->rcMax = _autopilot->getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1))->value().toInt(&convertOk); + info->rcMax = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1))->value().toInt(&convertOk); Q_ASSERT(convertOk); - float floatReversed = _autopilot->getParameterFact(FactSystem::defaultComponentId, revTpl.arg(i+1))->value().toFloat(&convertOk); + float floatReversed = getParameterFact(FactSystem::defaultComponentId, revTpl.arg(i+1))->value().toFloat(&convertOk); Q_ASSERT(convertOk); Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f); info->reversed = floatReversed == -1.0f; @@ -767,7 +696,7 @@ void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void) for (int i=0; igetParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[i].parameterName)->value().toInt(&convertOk); + paramChannel = getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[i].parameterName)->value().toInt(&convertOk); Q_ASSERT(convertOk); if (paramChannel != 0) { @@ -776,44 +705,16 @@ void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void) } } - _showMinMaxOnRadioWidgets(true); - _showTrimOnRadioWidgets(true); + _signalAllAttiudeValueChanges(); } -/// @brief Sets a connected Spektrum receiver into bind mode -void PX4RCCalibration::_spektrumBind(void) +void RadioComponentController::spektrumBindMode(int mode) { - - Q_ASSERT(_uas); - - QMessageBox bindTypeMsg(this); - - bindTypeMsg.setWindowModality(Qt::ApplicationModal); - QPushButton* dsm2Mode = bindTypeMsg.addButton("DSM2", QMessageBox::AcceptRole); - QPushButton* dsmx7Mode = bindTypeMsg.addButton("DSMX (7 channels or less)", QMessageBox::AcceptRole); - QPushButton* dsmx8Mode = bindTypeMsg.addButton("DSMX (8 channels or more)", QMessageBox::AcceptRole); - bindTypeMsg.addButton(QMessageBox::Cancel); - - bindTypeMsg.setWindowTitle(tr("Spektrum Bind")); - bindTypeMsg.setText(tr("Place Spektrum satellite receiver in bind mode. Select which mode below.")); - - int bindType = 0; - if (bindTypeMsg.exec() != QMessageBox::Cancel) { - if (bindTypeMsg.clickedButton() == dsm2Mode) { - bindType = 0; - } else if (bindTypeMsg.clickedButton() == dsmx7Mode) { - bindType = 1; - } else if (bindTypeMsg.clickedButton() == dsmx8Mode) { - bindType = 2; - } else { - Q_ASSERT(false); - } - _uas->pairRX(0, bindType); - } + _uas->pairRX(0, mode); } /// @brief Validates the current settings against the calibration rules resetting values as necessary. -void PX4RCCalibration::_validateCalibration(void) +void RadioComponentController::_validateCalibration(void) { for (int chan = 0; chan<_chanMax; chan++) { struct ChannelInfo* info = &_rgChannelInfo[chan]; @@ -822,7 +723,7 @@ void PX4RCCalibration::_validateCalibration(void) // Validate Min/Max values. Although the channel appears as available we still may // not have good min/max/trim values for it. Set to defaults if needed. if (info->rcMin > _rcCalPWMValidMinValue || info->rcMax < _rcCalPWMValidMaxValue) { - qCDebug(PX4RCCalibrationLog) << "_validateCalibration resetting channel" << chan; + qCDebug(RadioComponentControllerLog) << "_validateCalibration resetting channel" << chan; info->rcMin = _rcCalPWMDefaultMinValue; info->rcMax = _rcCalPWMDefaultMaxValue; info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2); @@ -848,7 +749,7 @@ void PX4RCCalibration::_validateCalibration(void) } } else { // Unavailable channels are set to defaults - qCDebug(PX4RCCalibrationLog) << "_validateCalibration resetting unavailable channel" << chan; + qCDebug(RadioComponentControllerLog) << "_validateCalibration resetting unavailable channel" << chan; info->rcMin = _rcCalPWMDefaultMinValue; info->rcMax = _rcCalPWMDefaultMaxValue; info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2); @@ -859,7 +760,7 @@ void PX4RCCalibration::_validateCalibration(void) /// @brief Saves the rc calibration values to the board parameters. -void PX4RCCalibration::_writeCalibration(void) +void RadioComponentController::_writeCalibration(void) { if (!_uas) return; @@ -877,10 +778,10 @@ void PX4RCCalibration::_writeCalibration(void) struct ChannelInfo* info = &_rgChannelInfo[chan]; int oneBasedChannel = chan + 1; - _autopilot->getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->setValue((float)info->rcTrim); - _autopilot->getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->setValue((float)info->rcMin); - _autopilot->getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->setValue((float)info->rcMax); - _autopilot->getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->setValue(info->reversed ? -1.0f : 1.0f); + getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->setValue((float)info->rcTrim); + getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->setValue((float)info->rcMin); + getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->setValue((float)info->rcMax); + getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->setValue(info->reversed ? -1.0f : 1.0f); } // Write function mapping parameters @@ -893,59 +794,20 @@ void PX4RCCalibration::_writeCalibration(void) // Note that the channel value is 1-based paramChannel = _rgFunctionChannelMapping[i] + 1; } - _autopilot->getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[i].parameterName)->setValue(paramChannel); + getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[i].parameterName)->setValue(paramChannel); } // If the RC_CHAN_COUNT parameter is available write the channel count - if (_autopilot->parameterExists(FactSystem::defaultComponentId, "RC_CHAN_CNT")) { - _autopilot->getParameterFact(FactSystem::defaultComponentId, "RC_CHAN_CNT")->setValue(_chanCount); + if (parameterExists(FactSystem::defaultComponentId, "RC_CHAN_CNT")) { + getParameterFact(FactSystem::defaultComponentId, "RC_CHAN_CNT")->setValue(_chanCount); } _stopCalibration(); _setInternalCalibrationValuesFromParameters(); } -void PX4RCCalibration::_updateView() -{ - // Update the available channels - for (int chan=0; chan<_chanCount; chan++) { - RCValueWidget* valueWidget = _rgRCValueMonitorWidget[chan]; - - valueWidget->setVisible(true); - _rgRCValueMonitorLabel[chan]->setVisible(true); - //qCDebug(PX4RCCalibrationLog) << "Visible" << valueWidget->objectName() << chan; - - struct ChannelInfo* info = &_rgChannelInfo[chan]; - valueWidget->setValueAndMinMax(_rcRawValue[chan], info->rcMin, info->rcMax); - valueWidget->setTrim(info->rcTrim); - valueWidget->setReversed(info->reversed); - } - - // Update attitude controls - for (int i=0; i<_attitudeControls; i++) { - struct AttitudeInfo* attitudeInfo = &_rgAttitudeControl[i]; - - if (_rgFunctionChannelMapping[attitudeInfo->function] != _chanMax) { - int channel = _rgFunctionChannelMapping[attitudeInfo->function]; - struct ChannelInfo* info = &_rgChannelInfo[channel]; - RCValueWidget* valueWidget = attitudeInfo->valueWidget; - - attitudeInfo->valueWidget->setValueAndMinMax(_rcRawValue[channel], info->rcMin, info->rcMax); - valueWidget->setTrim(info->rcTrim); - valueWidget->setReversed(info->reversed); - } - } - - // Hide non-available channels - for (int chan=_chanCount; chan<_chanMax; chan++) { - _rgRCValueMonitorWidget[chan]->setVisible(false); - _rgRCValueMonitorLabel[chan]->setVisible(false); - qCDebug(PX4RCCalibrationLog) << "Hiding channel" << _rgRCValueMonitorWidget[chan]->objectName() << chan; - } -} - /// @brief Starts the calibration process -void PX4RCCalibration::_startCalibration(void) +void RadioComponentController::_startCalibration(void) { Q_ASSERT(_chanCount >= _chanMinimum); @@ -954,15 +816,15 @@ void PX4RCCalibration::_startCalibration(void) // Let the mav known we are starting calibration. This should turn off motors and so forth. _uas->startCalibration(UASInterface::StartCalibrationRadio); - _ui->rcCalNext->setText(tr("Next")); - _ui->rcCalCancel->setEnabled(true); + _nextButton->setProperty("text", "Next"); + _cancelButton->setEnabled(true); _currentStep = 0; _setupCurrentState(); } /// @brief Cancels the calibration process, setting things back to initial state. -void PX4RCCalibration::_stopCalibration(void) +void RadioComponentController::_stopCalibration(void) { _currentStep = -1; @@ -973,83 +835,44 @@ void PX4RCCalibration::_stopCalibration(void) _resetInternalCalibrationValues(); } - _ui->rcCalStatus->clear(); + _statusText->setProperty("text", ""); - _ui->rcCalNext->setText(tr("Calibrate")); - _ui->rcCalNext->setEnabled(true); - _ui->rcCalCancel->setEnabled(false); - _ui->rcCalSkip->setEnabled(false); + _nextButton->setProperty("text", "Calibrate"); + _nextButton->setEnabled(true); + _cancelButton->setEnabled(false); + _skipButton->setEnabled(false); _setHelpImage(_imageCenter); } /// @brief Saves the current channel values, so that we can detect when the use moves an input. -void PX4RCCalibration::_rcCalSaveCurrentValues(void) +void RadioComponentController::_rcCalSaveCurrentValues(void) { - qCDebug(PX4RCCalibrationLog) << "_rcCalSaveCurrentValues"; + qCDebug(RadioComponentControllerLog) << "_rcCalSaveCurrentValues"; for (unsigned i = 0; i < _chanMax; i++) { _rcValueSave[i] = _rcRawValue[i]; } } /// @brief Set up the Save state of calibration. -void PX4RCCalibration::_rcCalSave(void) +void RadioComponentController::_rcCalSave(void) { _rcCalState = rcCalStateSave; - _ui->rcCalStatus->setText(tr("The current calibration settings are now displayed for each channel on screen.\n\n" - "Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values.")); + _statusText->setProperty("text", + "The current calibration settings are now displayed for each channel on screen.\n\n" + "Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values."); - _ui->rcCalNext->setEnabled(true); - _ui->rcCalSkip->setEnabled(false); - _ui->rcCalCancel->setEnabled(true); + _nextButton->setEnabled(true); + _skipButton->setEnabled(false); + _cancelButton->setEnabled(true); // This updates the internal values according to the validation rules. Then _updateView will tick and update ui // such that the settings that will be written our are displayed. _validateCalibration(); - - _showMinMaxOnRadioWidgets(true); -} - -/// @brief Shows or hides the min/max values of the channel widgets. -/// @param show true: show the min/max values, false: hide the min/max values -void PX4RCCalibration::_showMinMaxOnRadioWidgets(bool show) -{ - // Turn on min/max display for all radio widgets - for (int i=0; i<_chanMax; i++) { - RCValueWidget* radioWidget = _rgRCValueMonitorWidget[i]; - Q_ASSERT(radioWidget); - - radioWidget->showMinMax(show); - if (show) { - if (radioWidget->min() <= _rcCalPWMValidMinValue) { - radioWidget->setMinValid(true); - } - if (radioWidget->max() >= _rcCalPWMValidMaxValue) { - radioWidget->setMaxValid(true); - } - } else { - radioWidget->setMinValid(false); - radioWidget->setMaxValid(false); - } - } -} - -/// @brief Shows or hides the trim values of the channel widgets. -/// @param show true: show the trim values, false: hide the trim values -void PX4RCCalibration::_showTrimOnRadioWidgets(bool show) -{ - // Turn on trim display for all radio widgets - for (int i=0; i<_chanMax; i++) { - RCValueWidget* radioWidget = _rgRCValueMonitorWidget[i]; - Q_ASSERT(radioWidget); - - radioWidget->showTrim(show); - } } - -void PX4RCCalibration::_loadSettings(void) +void RadioComponentController::_loadSettings(void) { QSettings settings; @@ -1062,7 +885,7 @@ void PX4RCCalibration::_loadSettings(void) } } -void PX4RCCalibration::_storeSettings(void) +void RadioComponentController::_storeSettings(void) { QSettings settings; @@ -1071,29 +894,7 @@ void PX4RCCalibration::_storeSettings(void) settings.endGroup(); } -void PX4RCCalibration::_mode1Toggled(bool checked) -{ - if (checked) { - _transmitterMode = 1; - if (_currentStep != -1) { - const stateMachineEntry* state = _getStateMachineEntry(_currentStep); - _setHelpImage(state->image); - } - } -} - -void PX4RCCalibration::_mode2Toggled(bool checked) -{ - if (checked) { - _transmitterMode = 2; - if (_currentStep != -1) { - const stateMachineEntry* state = _getStateMachineEntry(_currentStep); - _setHelpImage(state->image); - } - } -} - -void PX4RCCalibration::_setHelpImage(const char* imageFile) +void RadioComponentController::_setHelpImage(const char* imageFile) { QString file = _imageFilePrefix; @@ -1106,7 +907,129 @@ void PX4RCCalibration::_setHelpImage(const char* imageFile) } file += imageFile; - qCDebug(PX4RCCalibrationLog) << "_setHelpImage" << file; + qCDebug(RadioComponentControllerLog) << "_setHelpImage" << file; - _ui->radioIcon->setPixmap(QPixmap(file)); + _imageHelp = file; + emit imageHelpChanged(file); +} + +int RadioComponentController::channelCount(void) +{ + return _chanCount; +} + +int RadioComponentController::rollChannelRCValue(void) +{ + if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax) { + return _rcRawValue[rcCalFunctionRoll]; + } else { + return 1500; + } +} + +int RadioComponentController::pitchChannelRCValue(void) +{ + if (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax) { + return _rcRawValue[rcCalFunctionPitch]; + } else { + return 1500; + } +} + +int RadioComponentController::yawChannelRCValue(void) +{ + if (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax) { + return _rcRawValue[rcCalFunctionYaw]; + } else { + return 1500; + } +} + +int RadioComponentController::throttleChannelRCValue(void) +{ + if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax) { + return _rcRawValue[rcCalFunctionThrottle]; + } else { + return 1500; + } +} + +bool RadioComponentController::rollChannelMapped(void) +{ + return _rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax; +} + +bool RadioComponentController::pitchChannelMapped(void) +{ + return _rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax; +} + +bool RadioComponentController::yawChannelMapped(void) +{ + return _rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax; +} + +bool RadioComponentController::throttleChannelMapped(void) +{ + return _rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax; +} + +bool RadioComponentController::rollChannelReversed(void) +{ + if (_rgFunctionChannelMapping[rcCalFunctionRoll] != _chanMax) { + return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionRoll]].reversed; + } else { + return false; + } +} + +bool RadioComponentController::pitchChannelReversed(void) +{ + if (_rgFunctionChannelMapping[rcCalFunctionPitch] != _chanMax) { + return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionPitch]].reversed; + } else { + return false; + } +} + +bool RadioComponentController::yawChannelReversed(void) +{ + if (_rgFunctionChannelMapping[rcCalFunctionYaw] != _chanMax) { + return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionYaw]].reversed; + } else { + return false; + } +} + +bool RadioComponentController::throttleChannelReversed(void) +{ + if (_rgFunctionChannelMapping[rcCalFunctionThrottle] != _chanMax) { + return _rgChannelInfo[_rgFunctionChannelMapping[rcCalFunctionThrottle]].reversed; + } else { + return false; + } +} + +void RadioComponentController::setTransmitterMode(int mode) +{ + if (mode == 1 || mode == 2) { + _transmitterMode = mode; + if (_currentStep != -1) { + const stateMachineEntry* state = _getStateMachineEntry(_currentStep); + _setHelpImage(state->image); + } + } +} + +void RadioComponentController::_signalAllAttiudeValueChanges(void) +{ + emit rollChannelMappedChanged(rollChannelMapped()); + emit pitchChannelMappedChanged(pitchChannelMapped()); + emit yawChannelMappedChanged(yawChannelMapped()); + emit throttleChannelMappedChanged(throttleChannelMapped()); + + emit rollChannelReversedChanged(rollChannelReversed()); + emit pitchChannelReversedChanged(pitchChannelReversed()); + emit yawChannelReversedChanged(yawChannelReversed()); + emit throttleChannelReversedChanged(throttleChannelReversed()); } diff --git a/src/ui/px4_configuration/PX4RCCalibration.h b/src/AutoPilotPlugins/PX4/RadioComponentController.h similarity index 64% rename from src/ui/px4_configuration/PX4RCCalibration.h rename to src/AutoPilotPlugins/PX4/RadioComponentController.h index 66d827e6f..d426e8fce 100644 --- a/src/ui/px4_configuration/PX4RCCalibration.h +++ b/src/AutoPilotPlugins/PX4/RadioComponentController.h @@ -2,7 +2,7 @@ QGroundControl Open Source Ground Control Station - (c) 2009, 2014 QGROUNDCONTROL PROJECT + (c) 2009, 2015 QGROUNDCONTROL PROJECT This file is part of the QGROUNDCONTROL project @@ -23,57 +23,123 @@ /// @file -/// @brief PX4 RC Calibration Widget +/// @brief Radio Config Qml Controller /// @author Don Gagne #include +#include "FactPanelController.h" #include "UASInterface.h" -#include "RCValueWidget.h" #include "QGCLoggingCategory.h" #include "AutoPilotPlugin.h" -#include "ui_PX4RCCalibration.h" +Q_DECLARE_LOGGING_CATEGORY(RadioComponentControllerLog) -Q_DECLARE_LOGGING_CATEGORY(PX4RCCalibrationLog) - -class PX4RCCalibrationTest; +//class RadioComponentControllerTest; namespace Ui { - class PX4RCCalibration; + class RadioComponentController; } -class PX4RCCalibration : public QWidget +class RadioComponentController : public FactPanelController { Q_OBJECT - friend class PX4RCCalibrationTest; ///< This allows our unit test to access internal information needed. + //friend class RadioComponentControllerTest; ///< This allows our unit test to access internal information needed. public: - explicit PX4RCCalibration(QWidget *parent = 0); - ~ PX4RCCalibration(); + RadioComponentController(void); + ~RadioComponentController(); + + Q_PROPERTY(int minChannelCount MEMBER _chanMinimum CONSTANT) + Q_PROPERTY(int channelCount READ channelCount NOTIFY channelCountChanged) + + Q_PROPERTY(QQuickItem* statusText MEMBER _statusText) + Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton) + Q_PROPERTY(QQuickItem* nextButton MEMBER _nextButton) + Q_PROPERTY(QQuickItem* skipButton MEMBER _skipButton) + + Q_PROPERTY(bool rollChannelMapped READ rollChannelMapped NOTIFY rollChannelMappedChanged) + Q_PROPERTY(bool pitchChannelMapped READ pitchChannelMapped NOTIFY pitchChannelMappedChanged) + Q_PROPERTY(bool yawChannelMapped READ yawChannelMapped NOTIFY yawChannelMappedChanged) + Q_PROPERTY(bool throttleChannelMapped READ throttleChannelMapped NOTIFY throttleChannelMappedChanged) + + Q_PROPERTY(int rollChannelRCValue READ rollChannelRCValue NOTIFY rollChannelRCValueChanged) + Q_PROPERTY(int pitchChannelRCValue READ pitchChannelRCValue NOTIFY pitchChannelRCValueChanged) + Q_PROPERTY(int yawChannelRCValue READ yawChannelRCValue NOTIFY yawChannelRCValueChanged) + Q_PROPERTY(int throttleChannelRCValue READ throttleChannelRCValue NOTIFY throttleChannelRCValueChanged) + + Q_PROPERTY(int rollChannelReversed READ rollChannelReversed NOTIFY rollChannelReversedChanged) + Q_PROPERTY(int pitchChannelReversed READ pitchChannelReversed NOTIFY pitchChannelReversedChanged) + Q_PROPERTY(int yawChannelReversed READ yawChannelReversed NOTIFY yawChannelReversedChanged) + Q_PROPERTY(int throttleChannelReversed READ throttleChannelReversed NOTIFY throttleChannelReversedChanged) + + Q_PROPERTY(int transmitterMode READ transmitterMode WRITE setTransmitterMode NOTIFY transmitterModeChanged) + Q_PROPERTY(QString imageHelp MEMBER _imageHelp NOTIFY imageHelpChanged) + + Q_ENUMS(BindModes) + enum BindModes { + DSM2, + DSMX7, + DSMX8 + }; + + Q_INVOKABLE void spektrumBindMode(int mode); + Q_INVOKABLE void cancelButtonClicked(void); + Q_INVOKABLE void skipButtonClicked(void); + Q_INVOKABLE void nextButtonClicked(void); + Q_INVOKABLE void start(void); + + int rollChannelRCValue(void); + int pitchChannelRCValue(void); + int yawChannelRCValue(void); + int throttleChannelRCValue(void); + + bool rollChannelMapped(void); + bool pitchChannelMapped(void); + bool yawChannelMapped(void); + bool throttleChannelMapped(void); + + bool rollChannelReversed(void); + bool pitchChannelReversed(void); + bool yawChannelReversed(void); + bool throttleChannelReversed(void); + + int channelCount(void); + + int transmitterMode(void) { return _transmitterMode; } + void setTransmitterMode(int mode); signals: - // @brief Signalled when in unit test mode and a message box should be displayed by the next button - void nextButtonMessageBoxDisplayed(void); - -private slots: - void _nextButton(void); - void _skipButton(void); - void _spektrumBind(void); + void channelCountChanged(int channelCount); + void channelRCValueChanged(int channel, int rcValue); - void _mode1Toggled(bool checked); - void _mode2Toggled(bool checked); + void rollChannelMappedChanged(bool mapped); + void pitchChannelMappedChanged(bool mapped); + void yawChannelMappedChanged(bool mapped); + void throttleChannelMappedChanged(bool mapped); - void _trimNYI(void); + void rollChannelRCValueChanged(int rcValue); + void pitchChannelRCValueChanged(int rcValue); + void yawChannelRCValueChanged(int rcValue); + void throttleChannelRCValueChanged(int rcValue); - void _updateView(void); + void rollChannelReversedChanged(bool reversed); + void pitchChannelReversedChanged(bool reversed); + void yawChannelReversedChanged(bool reversed); + void throttleChannelReversedChanged(bool reversed); + void imageHelpChanged(QString source); + void transmitterModeChanged(int mode); + + // @brief Signalled when in unit test mode and a message box should be displayed by the next button + void nextButtonMessageBoxDisplayed(void); + +private slots: void _remoteControlChannelRawChanged(int chan, float val); private: @@ -115,8 +181,8 @@ private: rcCalStateSave }; - typedef void (PX4RCCalibration::*inputFn)(enum rcCalFunctions function, int chan, int value); - typedef void (PX4RCCalibration::*buttonFn)(void); + typedef void (RadioComponentController::*inputFn)(enum rcCalFunctions function, int chan, int value); + typedef void (RadioComponentController::*buttonFn)(void); struct stateMachineEntry { enum rcCalFunctions function; const char* instructions; @@ -140,19 +206,11 @@ private: int rcTrim; ///< Trim position }; - /// @brief Information to relate a function to it's value widget. - struct AttitudeInfo { - enum rcCalFunctions function; - RCValueWidget* valueWidget; - }; - - // Methods - see source code for documentation - int _currentStep; ///< Current step of state machine const struct stateMachineEntry* _getStateMachineEntry(int step); - void _nextStep(void); + void _advanceState(void); void _setupCurrentState(void); void _inputCenterWaitBegin(enum rcCalFunctions function, int channel, int value); @@ -186,14 +244,13 @@ private: void _rcCalSaveCurrentValues(void); - void _showMinMaxOnRadioWidgets(bool show); - void _showTrimOnRadioWidgets(bool show); - void _setHelpImage(const char* imageFile); void _loadSettings(void); void _storeSettings(void); + void _signalAllAttiudeValueChanges(void); + // @brief Called by unit test code to set the mode to unit testing void _setUnitTestMode(void){ _unitTestMode = true; } @@ -225,7 +282,6 @@ private: int _rgFunctionChannelMapping[rcCalFunctionMax]; ///< Maps from rcCalFunctions to channel index. _chanMax indicates channel not set for this function. static const int _attitudeControls = 5; - struct AttitudeInfo _rgAttitudeControl[_attitudeControls]; int _chanCount; ///< Number of actual rc channels available static const int _chanMax = 18; ///< Maximum number of supported rc channels @@ -253,16 +309,6 @@ private: int _rcRawValue[_chanMax]; ///< Current set of raw channel values - RCValueWidget* _rgRCValueMonitorWidget[_chanMax]; ///< Array of radio channel value widgets - QLabel* _rgRCValueMonitorLabel[_chanMax]; ///< Array of radio channel value labels - - UASInterface* _uas; - QSharedPointer _autopilot; - - Ui::PX4RCCalibration* _ui; - - QTimer _updateTimer; ///< Timer used to update widgete ui - int _stickDetectChannel; int _stickDetectInitialValue; int _stickDetectValue; @@ -271,6 +317,13 @@ private: static const int _stickDetectSettleMSecs; bool _unitTestMode; + + QQuickItem* _statusText; + QQuickItem* _cancelButton; + QQuickItem* _nextButton; + QQuickItem* _skipButton; + + QString _imageHelp; }; -#endif // PX4RCCalibration_H +#endif // RadioComponentController_H diff --git a/src/AutoPilotPlugins/PX4/SafetyComponent.cc b/src/AutoPilotPlugins/PX4/SafetyComponent.cc index f530f4fd0..6e71a9941 100644 --- a/src/AutoPilotPlugins/PX4/SafetyComponent.cc +++ b/src/AutoPilotPlugins/PX4/SafetyComponent.cc @@ -25,7 +25,6 @@ /// @author Don Gagne #include "SafetyComponent.h" -#include "PX4RCCalibration.h" #include "QGCQmlWidgetHolder.h" #include "PX4AutoPilotPlugin.h" diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 9719936aa..f66e7b9bb 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -66,6 +66,7 @@ #include "AirframeComponentController.h" #include "SensorsComponentController.h" #include "PowerComponentController.h" +#include "RadioComponentController.h" #include "ScreenTools.h" #include "MavManager.h" @@ -324,6 +325,7 @@ void QGCApplication::_initCommon(void) qmlRegisterType("QGroundControl.Controllers", 1, 0, "AirframeComponentController"); qmlRegisterType("QGroundControl.Controllers", 1, 0, "SensorsComponentController"); qmlRegisterType("QGroundControl.Controllers", 1, 0, "PowerComponentController"); + qmlRegisterType("QGroundControl.Controllers", 1, 0, "RadioComponentController"); //-- Create QML Singleton Interfaces qmlRegisterSingletonType("QGroundControl.ScreenTools", 1, 0, "ScreenTools", screenToolsSingletonFactory); diff --git a/src/QmlControls/QGCView.qml b/src/QmlControls/QGCView.qml index 483fa6e62..01fe67292 100644 --- a/src/QmlControls/QGCView.qml +++ b/src/QmlControls/QGCView.qml @@ -153,8 +153,8 @@ FactPanel { QGCPalette { id: __qgcPal; colorGroupEnabled: true } QGCLabel { id: __textMeasure; text: "X"; visible: false } - property real __textHeight: __textMeasure.contentHeight - property real __textWidth: __textMeasure.contentWidth + property real defaultTextHeight: __textMeasure.contentHeight + property real defaultTextWidth: __textMeasure.contentWidth /// The width of the dialog panel in characters property int __dialogCharWidth: 75 @@ -271,7 +271,7 @@ FactPanel { // This is the main dialog panel which is anchored to the right edge Rectangle { id: __dialogPanel - width: __dialogCharWidth == -1 ? parent.width : __textWidth * __dialogCharWidth + width: __dialogCharWidth == -1 ? parent.width : defaultTextWidth * __dialogCharWidth height: parent.height anchors.left: __transparentSection.right color: __qgcPal.windowShadeDark @@ -287,7 +287,7 @@ FactPanel { } QGCLabel { - x: __textWidth + x: defaultTextWidth height: parent.height verticalAlignment: Text.AlignVCenter text: __dialogTitle diff --git a/src/ui/px4_configuration/PX4RCCalibration.ui b/src/ui/px4_configuration/PX4RCCalibration.ui deleted file mode 100644 index bf5abd0ce..000000000 --- a/src/ui/px4_configuration/PX4RCCalibration.ui +++ /dev/null @@ -1,1225 +0,0 @@ - - - PX4RCCalibration - - - - 0 - 0 - 720 - 501 - - - - - 0 - 0 - - - - - 720 - 501 - - - - Form - - - - - - - - color: rgb(128, 128, 128); - - - QFrame::Plain - - - 1 - - - 0 - - - Qt::Horizontal - - - - - - - Receiver - - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 40 - 20 - - - - - - - - Turn on transmitter - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Spektrum Bind - - - - - - - - - color: rgb(128, 128, 128); - - - QFrame::Plain - - - 1 - - - Qt::Horizontal - - - - - - - Attitude Controls - - - - - - - - - - 0 - 0 - - - - - 61 - 24 - - - - - 16 - - - - border: 1px solid rgb(128, 128, 128); -border-radius: 4px; -background-color: rgb(80, 80, 80);s - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 30 - - - - - 400 - 16777215 - - - - - - - - - 0 - 30 - - - - - - - - - 0 - 0 - - - - - 45 - 0 - - - - - 16 - - - - - - - Trim - - - - - - - - 0 - 0 - - - - - 61 - 24 - - - - - 16 - - - - border: 1px solid rgb(128, 128, 128); -border-radius: 4px; -background-color: rgb(80, 80, 80);s - - - Throttle - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 45 - 0 - - - - - 16 - - - - - - - Trim - - - false - - - - - - - - 0 - 0 - - - - - 45 - 0 - - - - - 16 - - - - - - - Trim - - - - - - - - 0 - 0 - - - - - 45 - 0 - - - - - 16 - - - - - - - Trim - - - - - - - - 0 - 30 - - - - - - - - - 0 - 30 - - - - - - - - - 0 - 0 - - - - - 61 - 24 - - - - - 16 - - - - border: 1px solid rgb(128, 128, 128); -border-radius: 4px; -background-color: rgb(80, 80, 80);s - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 61 - 24 - - - - - 16 - - - - border: 1px solid rgb(128, 128, 128); -border-radius: 4px; -background-color: rgb(80, 80, 80);s - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 61 - 24 - - - - - 16 - - - - border: 1px solid rgb(128, 128, 128); -border-radius: 4px; -background-color: rgb(80, 80, 80);s - - - Flaps - - - Qt::AlignCenter - - - - - - - - 0 - 30 - - - - - - - - - - - 0 - 0 - - - - - 0 - 100 - - - - Please turn on Radio - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - - - - Skip - - - - - - - Cancel - - - - - - - s - - - Start - - - - - - - - - Qt::Vertical - - - - 20 - 60 - - - - - - - - - - color: rgb(128, 128, 128); - - - QFrame::Plain - - - Qt::Vertical - - - - - - - - - color: rgb(128, 128, 128); - - - QFrame::Plain - - - Qt::Horizontal - - - - - - - -1 - - - QLayout::SetDefaultConstraint - - - 0 - - - 0 - - - - - Calibration Help - - - - - - - - 0 - 0 - - - - Mode 1 - - - - - - - - 0 - 0 - - - - Mode 2 - - - - - - - - - - 0 - 0 - - - - - 16777215 - 195 - - - - - - - :/res/calibration/radioCenter.png - - - Qt::AlignCenter - - - - - - - color: rgb(128, 128, 128); - - - QFrame::Plain - - - 1 - - - Qt::Horizontal - - - - - - - - 0 - 0 - - - - Channel Monitor - - - - - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 9 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 2 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 7 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 8 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 5 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 1 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 4 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 6 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 3 - - - - - - - - 0 - 0 - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - - - - - 122 - 0 - - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 18 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 10 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 15 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 13 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 17 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 11 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 14 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 12 - - - - - - - - 0 - 0 - - - - border: 1px solid white; -border-radius: 4px; -background-color: rgb(179, 179, 179); - - - 16 - - - - - - - - 0 - 0 - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - 122 - 0 - - - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - RCValueWidget - QWidget -
RCValueWidget.h
- 1 -
-
- - -
diff --git a/src/ui/px4_configuration/RCValueWidget.cc b/src/ui/px4_configuration/RCValueWidget.cc deleted file mode 100644 index 1761f7294..000000000 --- a/src/ui/px4_configuration/RCValueWidget.cc +++ /dev/null @@ -1,306 +0,0 @@ -/*===================================================================== - - QGroundControl Open Source Ground Control Station - - (c) 2009, 2014 QGROUNDCONTROL PROJECT - - This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - - ======================================================================*/ - -/// @file -/// @author Don Gagne - -#include "RCValueWidget.h" - -#include -#include - -#define DIMMEST_COLOR QColor::fromRgb(0,100,0) -#define MIDBRIGHT_COLOR QColor::fromRgb(0,180,0) -#define BRIGHTEST_COLOR QColor::fromRgb(64,255,0) - -RCValueWidget::RCValueWidget(QWidget *parent) : - QWidget(parent), - _smallMode(false), - _value(_centerValue), - _min(_centerValue), - _max(_centerValue), - _trim(_centerValue), - _minValid(false), - _maxValid(false), - _showMinMax(false), - _showTrim(false), - _fgColor(255, 255, 255) -{ - setAutoFillBackground(true); -} - -/// @brief Draws the control -void RCValueWidget::paintEvent(QPaintEvent *event) -{ - QPainter painter(this); - painter.setRenderHints(QPainter::Antialiasing); - - Q_UNUSED(event); - - int curVal = _value; - if (curVal > _maxRange) { - curVal = _maxRange; - } - if (curVal < _minRange) { - curVal = _minRange; - } - - QPen pen(_fgColor); - pen.setWidth(1); - painter.setPen(pen); - - if (_smallMode) { - painter.drawLine(0, height() / 2, width(), height() / 2); - } else { - // The value bar itself it centered in the control - QRect rectValueBar(0, (rect().height() - _barHeight)/2, rect().width() - 1, _barHeight); - - painter.drawRoundedRect(rectValueBar, _barHeight/2, _barHeight/2); - } - - // Draw the RC value circle - int radius = _smallMode ? 4 : _barHeight; - int curValNormalized; - if (_reversed) { - curValNormalized = _centerValue - (curVal - _centerValue); - } else { - curValNormalized = curVal; - } - QPoint ptCenter(width() * ((float)(curValNormalized-_minRange) / (_maxRange-_minRange)), height() / 2); - QBrush brush(QColor(128, 128, 128)); - painter.setBrush(brush); - painter.drawEllipse(ptCenter, radius, radius); - -#if 0 - int fontHeight = painter.fontMetrics().height(); - int rowHeigth = fontHeight + 2; - - painter.setBrush(Qt::Dense4Pattern); - painter.setPen(QColor::fromRgb(128,128,64)); - - int curVal = _value; - if (curVal > _maxRange) { - curVal = _maxRange; - } - if (curVal < _minRange) { - curVal = _minRange; - } - - if (isEnabled()) { - QLinearGradient hGradientBrush(0, 0, this->width(), this->height()); - hGradientBrush.setColorAt(0.0,DIMMEST_COLOR); - hGradientBrush.setColorAt(0.5,MIDBRIGHT_COLOR); - hGradientBrush.setColorAt(1.0, BRIGHTEST_COLOR); - - // Calculate how much horizontal space we need to show a min/max value. We must be able to display four numeric - // digits for the rc value, plus we add another digit for spacing. - int minMaxDisplayWidth = painter.fontMetrics().width("00000"); - - // Draw the value axis line with center and end point tick marks. We need to leave enough space on the left and the right - // for the Min/Max value displays. - QRect rcValueAxis(minMaxDisplayWidth, rowHeigth * 2, width() - (minMaxDisplayWidth * 2), rowHeigth); - int yLine = rcValueAxis.y() + rcValueAxis.height() / 2; - painter.drawLine(rcValueAxis.left(), yLine, rcValueAxis.right(), yLine); - painter.drawLine(rcValueAxis.left(), rcValueAxis.top(), rcValueAxis.left(), rcValueAxis.bottom()); - painter.drawLine(rcValueAxis.right(), rcValueAxis.top(), rcValueAxis.right(), rcValueAxis.bottom()); - painter.drawLine(rcValueAxis.left() + rcValueAxis.width() / 2, rcValueAxis.top(), rcValueAxis.left() + rcValueAxis.width() / 2, rcValueAxis.bottom()); - - painter.setPen(QColor::fromRgb(50,255,50)); - painter.setBrush(hGradientBrush); - - if (_showMinMax) { - QString text; - - // Draw the Min numeric value display to the left - painter.drawText(0, rowHeigth, minMaxDisplayWidth, fontHeight, Qt::AlignHCenter | Qt::AlignBottom, "Min"); - if (_minValid) { - text = QString::number(_min); - } else { - text = "----"; - } - painter.drawText(0, rowHeigth * 2, minMaxDisplayWidth, fontHeight, Qt::AlignHCenter | Qt::AlignBottom, text); - - // Draw the Max numeric value display to the right - painter.drawText(width() - minMaxDisplayWidth, rowHeigth, minMaxDisplayWidth, fontHeight, Qt::AlignHCenter | Qt::AlignBottom, "Max"); - if (_maxValid) { - text = QString::number(_max); - } else { - text = QString::number(_max); - } - painter.drawText(width() - minMaxDisplayWidth, rowHeigth * 2, minMaxDisplayWidth, fontHeight, Qt::AlignHCenter | Qt::AlignBottom, text); - - // Draw the Min/Max tick marks on the axis - int xTick; - if (_minValid) { - int xTick = rcValueAxis.left() + (rcValueAxis.width() * ((float)(_min-_minRange) / (_maxRange-_minRange))); - painter.drawLine(xTick, rcValueAxis.top(), xTick, rcValueAxis.bottom()); - } - if (_maxValid) { - xTick = rcValueAxis.left() + (rcValueAxis.width() * ((float)(_max-_minRange) / (_maxRange-_minRange))); - painter.drawLine(xTick, rcValueAxis.top(), xTick, rcValueAxis.bottom()); - } - } - - if (_showTrim) { - // Draw the Trim value pointer - _drawValuePointer(&painter, - rcValueAxis.left() + (rcValueAxis.width() * ((float)(_trim-_minRange) / (_maxRange-_minRange))), // x position for tip of triangle - (rowHeigth * 2) + (rowHeigth / 2) - 1, // y position for tip of triangle - rowHeigth / 2, // heigth of triangle - false); // draw upside down - - // Draw the Trim value label - QString trimStr = tr("Trim %1").arg(QString::number(_trim)); - - int trimTextWidth = painter.fontMetrics().width(trimStr); - - painter.drawText(rcValueAxis.left() + (rcValueAxis.width() * ((float)(_trim-_minRange) / (_maxRange-_minRange))) - (trimTextWidth / 2), - rowHeigth, - trimTextWidth, - fontHeight, - Qt::AlignLeft | Qt::AlignBottom, - trimStr); - } - - // Draw the RC value pointer - _drawValuePointer(&painter, - rcValueAxis.left() + (rcValueAxis.width() * ((float)(curVal-_minRange) / (_maxRange-_minRange))), // x position for tip of triangle - (rowHeigth * 2) + (rowHeigth / 2) + 1, // y position for tip of triangle - rowHeigth / 2, // heigth of triangle - true); // draw right side up - - // Draw the control value - QString valueStr = QString::number(_value); - - int valueTextWidth = painter.fontMetrics().width(valueStr); - - painter.drawText(rcValueAxis.left() + (rcValueAxis.width() * ((float)(_value-_minRange) / (_maxRange-_minRange))) - (valueTextWidth / 2), - rowHeigth * 3, - valueTextWidth, - fontHeight, - Qt::AlignLeft | Qt::AlignBottom, - valueStr); - - painter.setPen(QColor::fromRgb(0,128,0)); - painter.setBrush(hGradientBrush); - } else { - painter.setPen(QColor(Qt::gray)); - painter.drawText(0, 0, width(), height(), Qt::AlignHCenter | Qt::AlignVCenter, tr("not available")); - } -#endif -} - -void RCValueWidget::setValue(int value) -{ - _value = value; - update(); -} - -void RCValueWidget::showMinMax(bool show) -{ - _showMinMax = show; - update(); -} - -void RCValueWidget::showTrim(bool show) -{ - _showTrim = show; - update(); -} - -void RCValueWidget::setValueAndMinMax(int val, int min, int max) -{ - setValue(val); - setMinMax(min,max); -} - -void RCValueWidget::setMinMax(int min, int max) -{ - _min = min; - _max = max; - update(); -} - -void RCValueWidget::setMin(int min) -{ - _min = min; - update(); -} - -void RCValueWidget::setMax(int max) -{ - _max = max; - update(); -} - -void RCValueWidget::setTrim(int value) -{ - _trim = value; - update(); -} - -/// @brief Draw rc value pointer triangle. -/// @param painter Draw using this painter -/// @param x X position for tip of triangle -/// @param y Y position for tip of triangle -/// @param heigth Height of triangle -/// @param rightSideUp true: draw triangle right side up, false: draw triangle upside down -void RCValueWidget::_drawValuePointer(QPainter* painter, int xTip, int yTip, int height, bool rightSideUp) -{ - QPointF trianglePoints[3]; - - // Topmost tip of triangle points to value - trianglePoints[0].setX(xTip); - trianglePoints[0].setY(yTip); - - int yBottom; - if (rightSideUp) { - yBottom = yTip + height; - } else { - yBottom = yTip - height; - } - - // Right bottom tip of triangle - trianglePoints[1].setX(xTip + (height * 0.75)); - trianglePoints[1].setY(yBottom); - - // Left bottom tip of triangle - trianglePoints[2].setX(xTip - (height * 0.75)); - trianglePoints[2].setY(yBottom); - - painter->drawPolygon (trianglePoints, 3); -} - -/// @brief Set whether the Min range value is valid or not. -void RCValueWidget::setMinValid(bool valid) -{ - _minValid = valid; - update(); -} - -/// @brief Set whether the Max range value is valid or not. -void RCValueWidget::setMaxValid(bool valid) -{ - _maxValid = valid; - update(); -} diff --git a/src/ui/px4_configuration/RCValueWidget.h b/src/ui/px4_configuration/RCValueWidget.h deleted file mode 100644 index 03ce361f1..000000000 --- a/src/ui/px4_configuration/RCValueWidget.h +++ /dev/null @@ -1,111 +0,0 @@ -/*===================================================================== - - QGroundControl Open Source Ground Control Station - - (c) 2009, 2014 QGROUNDCONTROL PROJECT - - This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - - ======================================================================*/ - -/// @file -/// @brief Widget which shows current RC value on a bar with tick marks. -/// @author Don Gagne - -#ifndef RCValueWidget_H -#define RCValueWidget_H - -#include -#include - -/// @brief Widget which shows current RC value on a bar with tick marks. -class RCValueWidget : public QWidget -{ - Q_OBJECT - -public: - explicit RCValueWidget(QWidget *parent = 0); - - /// @brief Set the widget to display small value bar. - void setSmallMode(void) { _smallMode = true; } - - /// @brief Set the current RC value to display - void setValue(int value); - - /// @brief Set the current RC Value, Minimum RC Value and Maximum RC Value - void setValueAndMinMax(int val, int min, int max); - - void setMinMax(int min, int max); - void setMin(int min); - void setMax(int max); - - /// @brief Set whether the Min range value is valid or not. - void setMinValid(bool valid); - - /// @brief Set whether the Max range value is valid or not. - void setMaxValid(bool valid); - - /// @brief Sets the Trim value for the channel - void setTrim(int value); - - /// @brief Sets the reversed state of channel - /// @param reversed true: channel is reversed - void setReversed(bool reversed) { _reversed = reversed; } - - int value(void) { return _value; } ///< Returns the current RC Value set in the control - int min(void) { return _min; } ///< Returns the min value set in the control - int max(void) { return _max; } ///< Returns the max values set in the control - int trim(void) { return _trim; } ///< Returns the trim value set in the control - - void showMinMax(bool show); - bool isMinMaxShown() { return _showMinMax; } - bool isMinValid(void) { return _minValid; } - bool isMaxValid(void) { return _maxValid; } - - void showTrim(bool show); - bool isTrimShown() { return _showTrim; } - -protected: - virtual void paintEvent(QPaintEvent *event); - -private: - void _drawValuePointer(QPainter* painter, int xTip, int yTip, int height, bool rightSideUp); - - bool _smallMode; ///< true: draw small value bar, false: draw normal value bar - - int _value; ///< Current RC value - int _min; ///< Min RC value - int _max; ///< Max RC value - int _trim; ///< RC Value for Trim position - bool _reversed; ///< true: channel is reversed - - bool _minValid; ///< true: minimum value is valid - bool _maxValid; ///< true: maximum value is valid - - bool _showMinMax; ///< true: show min max values on display - bool _showTrim; ///< true: show trim value on display - - static const int _centerValue = 1500; ///< RC Value which is at center - static const int _maxDeltaRange = 650; ///< Delta around center value which is the max range for widget - static const int _minRange = _centerValue - _maxDeltaRange; ///< Smallest value widget can display - static const int _maxRange = _centerValue + _maxDeltaRange; ///< Largest value widget can display - - static const int _barHeight = 7; - - QColor _fgColor; -}; - -#endif -- 2.22.0