Browse Source

Convert RadioCal to Qml

QGC4.4
Don Gagne 10 years ago
parent
commit
20df7ebf6b
  1. 13
      QGCApplication.pro
  2. 7
      qgroundcontrol.qrc
  3. 1
      src/AutoPilotPlugins/PX4/PowerComponent.cc
  4. 8
      src/AutoPilotPlugins/PX4/RadioComponent.cc
  5. 510
      src/AutoPilotPlugins/PX4/RadioComponent.qml
  6. 727
      src/AutoPilotPlugins/PX4/RadioComponentController.cc
  7. 157
      src/AutoPilotPlugins/PX4/RadioComponentController.h
  8. 1
      src/AutoPilotPlugins/PX4/SafetyComponent.cc
  9. 2
      src/QGCApplication.cc
  10. 8
      src/QmlControls/QGCView.qml
  11. 1225
      src/ui/px4_configuration/PX4RCCalibration.ui
  12. 306
      src/ui/px4_configuration/RCValueWidget.cc
  13. 111
      src/ui/px4_configuration/RCValueWidget.h

13
QGCApplication.pro

@ -184,7 +184,6 @@ FORMS += \ @@ -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 += \ @@ -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 += \ @@ -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 += \ @@ -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 += \ @@ -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+= \ @@ -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 += \ @@ -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 \

7
qgroundcontrol.qrc

@ -50,6 +50,7 @@ @@ -50,6 +50,7 @@
<file alias="FirmwareUpgrade.qml">src/VehicleSetup/FirmwareUpgrade.qml</file>
<file alias="SetupParameterEditor.qml">src/VehicleSetup/SetupParameterEditor.qml</file>
<file alias="SafetyComponent.qml">src/AutoPilotPlugins/PX4/SafetyComponent.qml</file>
<file alias="RadioComponent.qml">src/AutoPilotPlugins/PX4/RadioComponent.qml</file>
<file alias="PowerComponent.qml">src/AutoPilotPlugins/PX4/PowerComponent.qml</file>
<file alias="SensorsComponent.qml">src/AutoPilotPlugins/PX4/SensorsComponent.qml</file>
<file alias="FlightModesComponent.qml">src/AutoPilotPlugins/PX4/FlightModesComponent.qml</file>
@ -220,7 +221,7 @@ @@ -220,7 +221,7 @@
</qresource>
<qresource prefix="/res/calibration">
<file alias ="accel_back.png">resources/calibration/accel_back.png</file>
<file alias="accel_back.png">resources/calibration/accel_back.png</file>
<file alias="accel_front.png">resources/calibration/accel_front.png</file>
<file alias="accel_right.png">resources/calibration/accel_right.png</file>
<file alias="accel_down.png">resources/calibration/accel_down.png</file>
@ -228,7 +229,7 @@ @@ -228,7 +229,7 @@
<file alias="accel_left.png">resources/calibration/accel_left.png</file>
</qresource>
<qresource prefix="/res/calibration/mode1">
<qresource prefix="/qml/calibration/mode1">
<file alias="radioCenter.png">resources/calibration/mode1/radioCenter.png</file>
<file alias="radioHome.png">resources/calibration/mode1/radioHome.png</file>
<file alias="radioRollLeft.png">resources/calibration/mode1/radioRollLeft.png</file>
@ -242,7 +243,7 @@ @@ -242,7 +243,7 @@
<file alias="radioSwitchMinMax.png">resources/calibration/mode1/radioSwitchMinMax.png</file>
</qresource>
<qresource prefix="/res/calibration/mode2">
<qresource prefix="/qml/calibration/mode2">
<file alias="radioCenter.png">resources/calibration/mode2/radioCenter.png</file>
<file alias="radioHome.png">resources/calibration/mode2/radioHome.png</file>
<file alias="radioRollLeft.png">resources/calibration/mode2/radioRollLeft.png</file>

1
src/AutoPilotPlugins/PX4/PowerComponent.cc

@ -25,7 +25,6 @@ @@ -25,7 +25,6 @@
/// @author Gus Grubba <mavlink@grubba.com>
#include "PowerComponent.h"
#include "PX4RCCalibration.h"
#include "QGCQmlWidgetHolder.h"
#include "PX4AutoPilotPlugin.h"

8
src/AutoPilotPlugins/PX4/RadioComponent.cc

@ -25,7 +25,7 @@ @@ -25,7 +25,7 @@
/// @author Don Gagne <don@thegagnes.com>
#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 @@ -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

510
src/AutoPilotPlugins/PX4/RadioComponent.qml

@ -0,0 +1,510 @@ @@ -0,0 +1,510 @@
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
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 <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @brief Radio Calibration
/// @author Don Gagne <don@thegagnes.com>
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
}

727
src/ui/px4_configuration/PX4RCCalibration.cc → src/AutoPilotPlugins/PX4/RadioComponentController.cc

File diff suppressed because it is too large Load Diff

157
src/ui/px4_configuration/PX4RCCalibration.h → src/AutoPilotPlugins/PX4/RadioComponentController.h

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
QGroundControl Open Source Ground Control Station
(c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
@ -23,57 +23,123 @@ @@ -23,57 +23,123 @@
/// @file
/// @brief PX4 RC Calibration Widget
/// @brief Radio Config Qml Controller
/// @author Don Gagne <don@thegagnes.com
#ifndef PX4RCCalibration_H
#define PX4RCCalibration_H
#ifndef RadioComponentController_H
#define RadioComponentController_H
#include <QWidget>
#include <QTimer>
#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: @@ -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: @@ -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: @@ -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: @@ -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: @@ -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<AutoPilotPlugin> _autopilot;
Ui::PX4RCCalibration* _ui;
QTimer _updateTimer; ///< Timer used to update widgete ui
int _stickDetectChannel;
int _stickDetectInitialValue;
int _stickDetectValue;
@ -271,6 +317,13 @@ private: @@ -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

1
src/AutoPilotPlugins/PX4/SafetyComponent.cc

@ -25,7 +25,6 @@ @@ -25,7 +25,6 @@
/// @author Don Gagne <don@thegagnes.com>
#include "SafetyComponent.h"
#include "PX4RCCalibration.h"
#include "QGCQmlWidgetHolder.h"
#include "PX4AutoPilotPlugin.h"

2
src/QGCApplication.cc

@ -66,6 +66,7 @@ @@ -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) @@ -324,6 +325,7 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<AirframeComponentController>("QGroundControl.Controllers", 1, 0, "AirframeComponentController");
qmlRegisterType<SensorsComponentController>("QGroundControl.Controllers", 1, 0, "SensorsComponentController");
qmlRegisterType<PowerComponentController>("QGroundControl.Controllers", 1, 0, "PowerComponentController");
qmlRegisterType<RadioComponentController>("QGroundControl.Controllers", 1, 0, "RadioComponentController");
//-- Create QML Singleton Interfaces
qmlRegisterSingletonType<ScreenTools>("QGroundControl.ScreenTools", 1, 0, "ScreenTools", screenToolsSingletonFactory);

8
src/QmlControls/QGCView.qml

@ -153,8 +153,8 @@ FactPanel { @@ -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 { @@ -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 { @@ -287,7 +287,7 @@ FactPanel {
}
QGCLabel {
x: __textWidth
x: defaultTextWidth
height: parent.height
verticalAlignment: Text.AlignVCenter
text: __dialogTitle

1225
src/ui/px4_configuration/PX4RCCalibration.ui

File diff suppressed because it is too large Load Diff

306
src/ui/px4_configuration/RCValueWidget.cc

@ -1,306 +0,0 @@ @@ -1,306 +0,0 @@
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
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 <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "RCValueWidget.h"
#include <QPainter>
#include <QDebug>
#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();
}

111
src/ui/px4_configuration/RCValueWidget.h

@ -1,111 +0,0 @@ @@ -1,111 +0,0 @@
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
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 <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @brief Widget which shows current RC value on a bar with tick marks.
/// @author Don Gagne <don@thegagnes.com>
#ifndef RCValueWidget_H
#define RCValueWidget_H
#include <QWidget>
#include <QColor>
/// @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
Loading…
Cancel
Save