Commit 20df7ebf authored by Don Gagne's avatar Don Gagne

Convert RadioCal to Qml

parent 85ad9e09
......@@ -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 \
......
......@@ -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 @@
</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 @@
<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 @@
<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>
......
......@@ -25,7 +25,6 @@
/// @author Gus Grubba <mavlink@grubba.com>
#include "PowerComponent.h"
#include "PX4RCCalibration.h"
#include "QGCQmlWidgetHolder.h"
#include "PX4AutoPilotPlugin.h"
......
......@@ -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
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
......
This diff is collapsed.
......@@ -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 @@
/// @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:
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<AutoPilotPlugin> _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
......@@ -25,7 +25,6 @@
/// @author Don Gagne <don@thegagnes.com>
#include "SafetyComponent.h"
#include "PX4RCCalibration.h"
#include "QGCQmlWidgetHolder.h"
#include "PX4AutoPilotPlugin.h"
......
......@@ -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<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);
......
......@@ -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
......
This diff is collapsed.
This diff is collapsed.
/*=====================================================================
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
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment