Commit e3132e65 authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #836 from DonLakeFlyer/RCWidget

RC Calibration Updates
parents 768e2408 0b1f2f63
......@@ -274,6 +274,9 @@ FORMS += \
src/ui/designer/QGCParamSlider.ui \
src/ui/designer/QGCActionButton.ui \
src/ui/designer/QGCCommandButton.ui \
src/ui/designer/QGCComboBox.ui \
src/ui/designer/QGCTextLabel.ui \
src/ui/designer/QGCXYPlot.ui \
src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui \
src/ui/QGCUASFileViewMulti.ui \
......@@ -309,8 +312,6 @@ FORMS += \
src/ui/QGCHilFlightGearConfiguration.ui \
src/ui/QGCHilJSBSimConfiguration.ui \
src/ui/QGCHilXPlaneConfiguration.ui \
src/ui/designer/QGCComboBox.ui \
src/ui/designer/QGCTextLabel.ui \
src/ui/uas/UASQuickView.ui \
src/ui/uas/UASQuickViewItemSelect.ui \
src/ui/uas/UASActionsWidget.ui \
......@@ -355,7 +356,6 @@ FORMS += \
src/ui/px4_configuration/QGCPX4MulticopterConfig.ui \
src/ui/px4_configuration/QGCPX4SensorCalibration.ui \
src/ui/px4_configuration/PX4RCCalibration.ui \
src/ui/designer/QGCXYPlot.ui \
src/ui/QGCUASFileView.ui
HEADERS += \
......@@ -435,6 +435,11 @@ HEADERS += \
src/ui/designer/QGCParamSlider.h \
src/ui/designer/QGCCommandButton.h \
src/ui/designer/QGCToolWidgetItem.h \
src/ui/designer/QGCComboBox.h \
src/ui/designer/QGCTextLabel.h \
src/ui/designer/QGCRadioChannelDisplay.h \
src/ui/designer/QGCXYPlot.h \
src/ui/designer/RCChannelWidget.h \
src/ui/QGCMAVLinkLogPlayer.h \
src/comm/MAVLinkSimulationWaypointPlanner.h \
src/comm/MAVLinkSimulationMAV.h \
......@@ -483,8 +488,6 @@ HEADERS += \
src/ui/QGCHilFlightGearConfiguration.h \
src/ui/QGCHilJSBSimConfiguration.h \
src/ui/QGCHilXPlaneConfiguration.h \
src/ui/designer/QGCComboBox.h \
src/ui/designer/QGCTextLabel.h \
src/ui/submainwindow.h \
src/ui/uas/UASQuickView.h \
src/ui/uas/UASQuickViewItem.h \
......@@ -493,7 +496,6 @@ HEADERS += \
src/ui/uas/UASQuickViewTextItem.h \
src/ui/uas/UASQuickViewGaugeItem.h \
src/ui/uas/UASActionsWidget.h \
src/ui/designer/QGCRadioChannelDisplay.h \
src/ui/QGCTabbedInfoView.h \
src/ui/UASRawStatusView.h \
src/ui/PrimaryFlightDisplay.h \
......@@ -544,7 +546,6 @@ HEADERS += \
src/ui/px4_configuration/QGCPX4MulticopterConfig.h \
src/ui/px4_configuration/QGCPX4SensorCalibration.h \
src/ui/px4_configuration/PX4RCCalibration.h \
src/ui/designer/QGCXYPlot.h \
src/ui/menuactionhelper.h \
src/uas/UASManagerInterface.h \
src/uas/QGCUASParamManagerInterface.h \
......@@ -625,6 +626,11 @@ SOURCES += \
src/ui/designer/QGCParamSlider.cc \
src/ui/designer/QGCCommandButton.cc \
src/ui/designer/QGCToolWidgetItem.cc \
src/ui/designer/QGCComboBox.cc \
src/ui/designer/QGCTextLabel.cc \
src/ui/designer/QGCRadioChannelDisplay.cpp \
src/ui/designer/QGCXYPlot.cc \
src/ui/designer/RCChannelWidget.cc \
src/ui/QGCMAVLinkLogPlayer.cc \
src/comm/MAVLinkSimulationWaypointPlanner.cc \
src/comm/MAVLinkSimulationMAV.cc \
......@@ -671,8 +677,6 @@ SOURCES += \
src/ui/QGCHilFlightGearConfiguration.cc \
src/ui/QGCHilJSBSimConfiguration.cc \
src/ui/QGCHilXPlaneConfiguration.cc \
src/ui/designer/QGCComboBox.cc \
src/ui/designer/QGCTextLabel.cc \
src/ui/submainwindow.cpp \
src/ui/uas/UASQuickViewItem.cc \
src/ui/uas/UASQuickView.cc \
......@@ -681,7 +685,6 @@ SOURCES += \
src/ui/uas/UASQuickViewGaugeItem.cc \
src/ui/uas/UASQuickViewItemSelect.cc \
src/ui/uas/UASActionsWidget.cpp \
src/ui/designer/QGCRadioChannelDisplay.cpp \
src/ui/QGCTabbedInfoView.cpp \
src/ui/UASRawStatusView.cpp \
src/ui/PrimaryFlightDisplay.cc \
......@@ -732,7 +735,6 @@ SOURCES += \
src/ui/px4_configuration/QGCPX4MulticopterConfig.cc \
src/ui/px4_configuration/QGCPX4SensorCalibration.cc \
src/ui/px4_configuration/PX4RCCalibration.cc \
src/ui/designer/QGCXYPlot.cc \
src/ui/menuactionhelper.cpp \
src/uas/QGCUASFileManager.cc \
src/ui/QGCUASFileView.cc \
......
......@@ -38,7 +38,7 @@ class MockQGCUASParamManager : public QGCUASParamManagerInterface
signals:
// The following QGCSUASParamManagerInterface signals are supported
// currently none
void parameterListUpToDate(); // You can connect to this signal, but it will never be emitted
public:
// Implemented QGCSUASParamManager overrides
......
......@@ -97,32 +97,13 @@ void PX4RCCalibrationTest::init(void)
_statusLabel = _calWidget->findChild<QLabel*>("rcCalStatus");
Q_ASSERT(_statusLabel);
// Need to make sure standard channel indices are less then 4. Otherwise our _rgRadioWidget array won't work correctly.
Q_ASSERT(PX4RCCalibration::rcCalFunctionRoll >= 0 && PX4RCCalibration::rcCalFunctionRoll < 4);
Q_ASSERT(PX4RCCalibration::rcCalFunctionPitch >= 0 && PX4RCCalibration::rcCalFunctionPitch < 4);
Q_ASSERT(PX4RCCalibration::rcCalFunctionYaw >= 0 && PX4RCCalibration::rcCalFunctionYaw < 4);
Q_ASSERT(PX4RCCalibration::rcCalFunctionThrottle >= 0 && PX4RCCalibration::rcCalFunctionThrottle < 4);
_rgAttitudeRadioWidget[PX4RCCalibration::rcCalFunctionRoll] = _calWidget->findChild<QGCRadioChannelDisplay*>("rollWidget");
_rgAttitudeRadioWidget[PX4RCCalibration::rcCalFunctionPitch] = _calWidget->findChild<QGCRadioChannelDisplay*>("pitchWidget");
_rgAttitudeRadioWidget[PX4RCCalibration::rcCalFunctionYaw] = _calWidget->findChild<QGCRadioChannelDisplay*>("yawWidget");
_rgAttitudeRadioWidget[PX4RCCalibration::rcCalFunctionThrottle] = _calWidget->findChild<QGCRadioChannelDisplay*>("throttleWidget");
Q_ASSERT(_rgAttitudeRadioWidget[PX4RCCalibration::rcCalFunctionRoll]);
Q_ASSERT(_rgAttitudeRadioWidget[PX4RCCalibration::rcCalFunctionPitch]);
Q_ASSERT(_rgAttitudeRadioWidget[PX4RCCalibration::rcCalFunctionYaw]);
Q_ASSERT(_rgAttitudeRadioWidget[PX4RCCalibration::rcCalFunctionThrottle]);
for (size_t i=0; i<PX4RCCalibration::_chanMax; i++) {
QString radioWidgetName("radio%1Widget");
QString radioWidgetUserName("Radio %1");
QGCRadioChannelDisplay* radioWidget = _calWidget->findChild<QGCRadioChannelDisplay*>(radioWidgetName.arg(i+1));
RCChannelWidget* radioWidget = _calWidget->findChild<RCChannelWidget*>(radioWidgetName.arg(i+1));
Q_ASSERT(radioWidget);
radioWidget->setOrientation(Qt::Horizontal);
radioWidget->setName(radioWidgetUserName.arg(i+1));
_rgRadioWidget[i] = radioWidget;
}
}
......@@ -177,7 +158,7 @@ void PX4RCCalibrationTest::_liveRC_test(void)
}
for (int i=0; i<PX4RCCalibration::_chanMax; i++) {
QGCRadioChannelDisplay* radioWidget = _rgRadioWidget[i];
RCChannelWidget* radioWidget = _rgRadioWidget[i];
Q_ASSERT(radioWidget);
QCOMPARE(radioWidget->value(), PX4RCCalibration::_rcCalPWMValidMinValue);
......@@ -323,20 +304,9 @@ StartOver:
CHK_BUTTONS(cancelButtonMask);
// Also at this point the radio channel widgets should be displaying the current min/max we just set.
// Check both the Attitude Control widgets as well as generic channel widgets.
Q_ASSERT(PX4RCCalibration::rcCalFunctionFirstAttitudeFunction == 0);
for (int i=0; i<PX4RCCalibration::rcCalFunctionLastAttitudeFunction; i++) {
QGCRadioChannelDisplay* radioWidget = _rgAttitudeRadioWidget[i];
Q_ASSERT(radioWidget);
QCOMPARE(radioWidget->isMinMaxShown(), true);
QCOMPARE(radioWidget->min(), PX4RCCalibration::_rcCalPWMValidMinValue);
QCOMPARE(radioWidget->max(), PX4RCCalibration::_rcCalPWMValidMaxValue);
}
for (int i=0; i<PX4RCCalibration::_chanMax; i++) {
QGCRadioChannelDisplay* radioWidget = _rgRadioWidget[i];
RCChannelWidget* radioWidget = _rgRadioWidget[i];
Q_ASSERT(radioWidget);
QCOMPARE(radioWidget->isMinMaxShown(), true);
......
......@@ -93,8 +93,7 @@ private:
QPushButton* _tryAgainButton;
QLabel* _statusLabel;
QGCRadioChannelDisplay* _rgAttitudeRadioWidget[4];
QGCRadioChannelDisplay* _rgRadioWidget[PX4RCCalibration::_chanMax];
RCChannelWidget* _rgRadioWidget[PX4RCCalibration::_chanMax];
};
DECLARE_TEST(PX4RCCalibrationTest)
......
......@@ -206,14 +206,14 @@ void QGCVehicleConfig::startCalibrationRC()
ui->rcCalibrationButton->setText(tr("Stop RC Calibration"));
resetCalibrationRC();
calibrationEnabled = true;
ui->rollWidget->showMinMax();
ui->pitchWidget->showMinMax();
ui->yawWidget->showMinMax();
ui->throttleWidget->showMinMax();
ui->radio5Widget->showMinMax();
ui->radio6Widget->showMinMax();
ui->radio7Widget->showMinMax();
ui->radio8Widget->showMinMax();
ui->rollWidget->showMinMax(true);
ui->pitchWidget->showMinMax(true);
ui->yawWidget->showMinMax(true);
ui->throttleWidget->showMinMax(true);
ui->radio5Widget->showMinMax(true);
ui->radio6Widget->showMinMax(true);
ui->radio7Widget->showMinMax(true);
ui->radio8Widget->showMinMax(true);
}
void QGCVehicleConfig::stopCalibrationRC()
......@@ -222,14 +222,14 @@ void QGCVehicleConfig::stopCalibrationRC()
calibrationEnabled = false;
ui->rcTypeComboBox->setEnabled(true);
ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
ui->rollWidget->hideMinMax();
ui->pitchWidget->hideMinMax();
ui->yawWidget->hideMinMax();
ui->throttleWidget->hideMinMax();
ui->radio5Widget->hideMinMax();
ui->radio6Widget->hideMinMax();
ui->radio7Widget->hideMinMax();
ui->radio8Widget->hideMinMax();
ui->rollWidget->showMinMax(false);
ui->pitchWidget->showMinMax(false);
ui->yawWidget->showMinMax(false);
ui->throttleWidget->showMinMax(false);
ui->radio5Widget->showMinMax(false);
ui->radio6Widget->showMinMax(false);
ui->radio7Widget->showMinMax(false);
ui->radio8Widget->showMinMax(false);
QString statusstr;
statusstr = "Below you will find the detected radio calibration information that will be sent to the autopilot\n";
statusstr += "Normal values are around 1100 to 1900, with disconnected channels reading very close to 1500\n\n";
......
......@@ -176,14 +176,14 @@ void RadioCalibrationConfig::calibrateButtonClicked()
rcMin[i] = 1500;
rcMax[i] = 1500;
}
ui.rollWidget->showMinMax();
ui.pitchWidget->showMinMax();
ui.yawWidget->showMinMax();
ui.radio5Widget->showMinMax();
ui.radio6Widget->showMinMax();
ui.radio7Widget->showMinMax();
ui.throttleWidget->showMinMax();
ui.radio8Widget->showMinMax();
ui.rollWidget->showMinMax(true);
ui.pitchWidget->showMinMax(true);
ui.yawWidget->showMinMax(true);
ui.radio5Widget->showMinMax(true);
ui.radio6Widget->showMinMax(true);
ui.radio7Widget->showMinMax(true);
ui.throttleWidget->showMinMax(true);
ui.radio8Widget->showMinMax(true);
QMessageBox::information(0,"Information","Click OK, then move all sticks to their extreme positions, watching the min/max values to ensure you get the most range from your controller. This includes all switches");
}
else
......@@ -192,14 +192,14 @@ void RadioCalibrationConfig::calibrateButtonClicked()
QMessageBox::information(0,"Trims","Ensure all sticks are centered and throttle is in the downmost position, click OK to continue");
///TODO: Set trims!
m_calibrationEnabled = false;
ui.rollWidget->hideMinMax();
ui.pitchWidget->hideMinMax();
ui.yawWidget->hideMinMax();
ui.radio5Widget->hideMinMax();
ui.radio6Widget->hideMinMax();
ui.throttleWidget->hideMinMax();
ui.radio7Widget->hideMinMax();
ui.radio8Widget->hideMinMax();
ui.rollWidget->showMinMax(false);
ui.pitchWidget->showMinMax(false);
ui.yawWidget->showMinMax(false);
ui.radio5Widget->showMinMax(false);
ui.radio6Widget->showMinMax(false);
ui.throttleWidget->showMinMax(false);
ui.radio7Widget->showMinMax(false);
ui.radio8Widget->showMinMax(false);
QString statusstr;
statusstr = "Below you will find the detected radio calibration information that will be sent to the autopilot\n";
statusstr += "Normal values are around 1100 to 1900, with disconnected channels reading very close to 1500\n\n";
......
/*=====================================================================
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 "RCChannelWidget.h"
#include <QPainter>
#define DIMMEST_COLOR QColor::fromRgb(0,100,0)
#define MIDBRIGHT_COLOR QColor::fromRgb(0,180,0)
#define BRIGHTEST_COLOR QColor::fromRgb(64,255,0)
RCChannelWidget::RCChannelWidget(QWidget *parent) :
QGroupBox(parent),
_value(_centerValue),
_min(_centerValue),
_max(_centerValue),
_trim(_centerValue),
_showMinMax(false),
_showTrim(false)
{
}
/// @brief Draws the control
void RCChannelWidget::paintEvent(QPaintEvent *event)
{
// Let the group box draw the outer border
QGroupBox::paintEvent(event);
// Now we draw the innner contents
QPainter painter(this);
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) {
// Draw the Min numeric value display to the left
painter.drawText(0, rowHeigth, minMaxDisplayWidth, fontHeight, Qt::AlignHCenter | Qt::AlignBottom, "Min");
painter.drawText(0, rowHeigth * 2, minMaxDisplayWidth, fontHeight, Qt::AlignHCenter | Qt::AlignBottom, QString::number(_min));
// Draw the Max numeric value display to the right
painter.drawText(width() - minMaxDisplayWidth, rowHeigth, minMaxDisplayWidth, fontHeight, Qt::AlignHCenter | Qt::AlignBottom, "Max");
painter.drawText(width() - minMaxDisplayWidth, rowHeigth * 2, minMaxDisplayWidth, fontHeight, Qt::AlignHCenter | Qt::AlignBottom, QString::number(_max));
// Draw the Min/Max tick marks on the axis
int xTick = rcValueAxis.left() + (rcValueAxis.width() * ((float)(_min-_minRange) / (_maxRange-_minRange)));
painter.drawLine(xTick, rcValueAxis.top(), xTick, rcValueAxis.bottom());
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"));
}
}
void RCChannelWidget::setValue(int value)
{
_value = value;
update();
}
void RCChannelWidget::showMinMax(bool show)
{
_showMinMax = show;
update();
}
void RCChannelWidget::showTrim(bool show)
{
_showTrim = show;
update();
}
void RCChannelWidget::setValueAndMinMax(int val, int min, int max)
{
setValue(val);
setMinMax(min,max);
}
void RCChannelWidget::setMinMax(int min, int max)
{
_min = min;
_max = max;
update();
}
void RCChannelWidget::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 RCChannelWidget::_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);
}
/*=====================================================================
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>
#ifndef RCChannelWidget_H
#define RCChannelWidget_H
#include <QGroupBox>
/// @brief RC Channel Widget - UI Widget based on QGroupBox which displays the current calibration settings
/// for an RC channel.
class RCChannelWidget : public QGroupBox
{
Q_OBJECT
public:
explicit RCChannelWidget(QWidget *parent = 0);
/// @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);
/// @brief Sets the Trim value for the channel
void setTrim(int value);
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; }
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);
int _value; ///< Current RC value
int _min; ///< Min RC value
int _max; ///< Max RC value
int _trim; ///< RC Value for Trim position
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 = 700; ///< 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
};
#endif
......@@ -59,40 +59,21 @@ PX4RCCalibration::PX4RCCalibration(QWidget *parent) :
_chanCount(0),
_rcCalState(rcCalStateChannelWait),
_mav(NULL),
_paramMgr(NULL),
_parameterListUpToDateSignalled(false),
_ui(new Ui::PX4RCCalibration)
{
_ui->setupUi(this);
// Setup up attitude control radio widgets
_ui->rollWidget->setName(_rgFunctionInfo[rcCalFunctionRoll].functionName);
_ui->pitchWidget->setName(_rgFunctionInfo[rcCalFunctionPitch].functionName);
_ui->yawWidget->setName(_rgFunctionInfo[rcCalFunctionYaw].functionName);
_ui->throttleWidget->setName(_rgFunctionInfo[rcCalFunctionThrottle].functionName);
_ui->rollWidget->setOrientation(Qt::Horizontal);
_ui->yawWidget->setOrientation(Qt::Horizontal);
// Initialize arrays of widget control pointers. This allows for more efficient code writing using "for" loops.
// Need to make sure standard channel indices are less then 4. Otherwise our _rgRadioWidget array won't work correctly.
Q_ASSERT(rcCalFunctionRoll >= 0 && rcCalFunctionRoll < 4);
Q_ASSERT(rcCalFunctionPitch >= 0 && rcCalFunctionPitch < 4);
Q_ASSERT(rcCalFunctionYaw >= 0 && rcCalFunctionYaw < 4);
Q_ASSERT(rcCalFunctionThrottle >= 0 && rcCalFunctionThrottle < 4);
_rgAttitudeRadioWidget[rcCalFunctionRoll] = _ui->rollWidget;
_rgAttitudeRadioWidget[rcCalFunctionPitch] = _ui->pitchWidget;
_rgAttitudeRadioWidget[rcCalFunctionYaw] = _ui->yawWidget;
_rgAttitudeRadioWidget[rcCalFunctionThrottle] = _ui->throttleWidget;
for (int chan=0; chan<_chanMax; chan++) {
QString radioWidgetName("radio%1Widget");
QString radioWidgetUserName("Radio %1");
QString radioWidgetUserName("Channel %1");
QGCRadioChannelDisplay* radioWidget = findChild<QGCRadioChannelDisplay*>(radioWidgetName.arg(chan+1));
RCChannelWidget* radioWidget = findChild<RCChannelWidget*>(radioWidgetName.arg(chan+1));
Q_ASSERT(radioWidget);
radioWidget->setOrientation(Qt::Horizontal);
radioWidget->setName(radioWidgetUserName.arg(chan+1));
radioWidget->setTitle(radioWidgetUserName.arg(chan+1));
_rgRadioWidget[chan] = radioWidget;
}
......@@ -132,9 +113,6 @@ PX4RCCalibration::PX4RCCalibration(QWidget *parent) :
/// @brief Resets internal calibration values to their initial state in preparation for a new calibration sequence.
void PX4RCCalibration::_resetInternalCalibrationValues(void)
{
// Detect channel count again
_chanCount = 0;
// Set all raw channels to not reversed and center point values
for (size_t i=0; i<_chanMax; i++) {
struct ChannelInfo* info = &_rgChannelInfo[i];
......@@ -151,6 +129,91 @@ void PX4RCCalibration::_resetInternalCalibrationValues(void)
}
_showMinMaxOnRadioWidgets(false);
_showTrimOnRadioWidgets(false);
}
/// @brief Resets internal calibration values to their initial state in preparation for a new calibration sequence.
void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void)
{
Q_ASSERT(_paramMgr);
if (_parameterListUpToDateSignalled) {
// Initialize all function mappings to not set
for (size_t i=0; i<_chanMax; i++) {
struct ChannelInfo* info = &_rgChannelInfo[i];
info->function = rcCalFunctionMax;
}
for (size_t i=0; i<rcCalFunctionMax; i++) {
_rgFunctionChannelMapping[i] = _chanMax;
}
// FIXME: Hardwired component id
// Pull parameters and update
QString minTpl("RC%1_MIN");
QString maxTpl("RC%1_MAX");
QString trimTpl("RC%1_TRIM");
QString revTpl("RC%1_REV");
QVariant value;
bool paramFound;
bool convertOk;
for (int i = 0; i < _chanMax; ++i) {
struct ChannelInfo* info = &_rgChannelInfo[i];
paramFound = _paramMgr->getParameterValue(50, trimTpl.arg(i+1), value);
Q_ASSERT(paramFound);
if (paramFound) {
info->rcTrim = value.toInt(&convertOk);
Q_ASSERT(convertOk);
}
paramFound = _paramMgr->getParameterValue(50, minTpl.arg(i+1), value);
Q_ASSERT(paramFound);
if (paramFound) {
info->rcMin = value.toInt(&convertOk);
Q_ASSERT(convertOk);
}
paramFound = _paramMgr->getParameterValue(50, maxTpl.arg(i+1), value);
Q_ASSERT(paramFound);
if (paramFound) {
info->rcMax = value.toInt(&convertOk);
Q_ASSERT(convertOk);
}
paramFound = _paramMgr->getParameterValue(50, revTpl.arg(i+1), value);
Q_ASSERT(paramFound);
if (paramFound) {
float floatReversed = value.toFloat(&convertOk);
Q_ASSERT(convertOk);
Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f);
info->reversed = floatReversed == -1.0f;
}
}
for (int i=0; i<rcCalFunctionMax; i++) {
int32_t paramChannel;
paramFound = _paramMgr->getParameterValue(50, _rgFunctionInfo[i].parameterName, value);
Q_ASSERT(paramFound);
if (paramFound) {
paramChannel = value.toInt(&convertOk);
Q_ASSERT(convertOk);
if (paramChannel != 0) {
_rgFunctionChannelMapping[i] = paramChannel - 1;
_rgChannelInfo[paramChannel - 1].function = (enum rcCalFunctions)i;
}
}
}
_showMinMaxOnRadioWidgets(true);
_showTrimOnRadioWidgets(true);
}
}
/// @brief Sets a connected Spektrum receiver into bind mode
......@@ -188,6 +251,8 @@ void PX4RCCalibration::_setActiveUAS(UASInterface* active)
// Disconnect old signals
if (_mav) {
disconnect(_mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(_remoteControlChannelRawChanged(int,float)));
disconnect(_paramMgr, SIGNAL(parameterListUpToDate()), this, SLOT(_parameterListUpToDate()));
_paramMgr = NULL;
}
_mav = active;
......@@ -198,6 +263,12 @@ void PX4RCCalibration::_setActiveUAS(UASInterface* active)
Q_UNUSED(fSucceeded);
fSucceeded = connect(_mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(_remoteControlChannelRawChanged(int,float)));
Q_ASSERT(fSucceeded);
_paramMgr = _mav->getParamManager();
Q_ASSERT(_paramMgr);
fSucceeded = connect(_paramMgr, SIGNAL(parameterListUpToDate()), this, SLOT(_parameterListUpToDate()));
Q_ASSERT(fSucceeded);
}
setEnabled(_mav ? true : false);
......@@ -361,7 +432,17 @@ void PX4RCCalibration::_remoteControlChannelRawChanged(int chan, float fval)
break;
case rcCalStateTrims:
// We only care about the throttle channel
// Update the trim values for attitude functions only
if (_rgChannelInfo[chan].function >= rcCalFunctionFirstAttitudeFunction && _rgChannelInfo[chan].function <= rcCalFunctionLastAttitudeFunction) {
int mappedChannel = _rgFunctionChannelMapping[_rgChannelInfo[chan].function];
// All Attitude Functions should be mapped
Q_ASSERT(mappedChannel != rcCalFunctionMax);
_rgChannelInfo[mappedChannel].rcTrim = _rcRawValue[mappedChannel];
}
// Once the throttle is lowered we enable the next button
Q_ASSERT(_rgFunctionChannelMapping[rcCalFunctionThrottle] != rcCalFunctionMax);
if (chan == _rgFunctionChannelMapping[rcCalFunctionThrottle]) {
bool enableNext = false;
......@@ -383,24 +464,13 @@ void PX4RCCalibration::_remoteControlChannelRawChanged(int chan, float fval)
void PX4RCCalibration::_updateView()
{
// Update Attitude Function channel widgets, disbaled if unmapped
for (int i=rcCalFunctionFirstAttitudeFunction; i<=rcCalFunctionLastAttitudeFunction; i++) {
int mappedChannel = _rgFunctionChannelMapping[i];
if (mappedChannel != _chanMax) {
struct ChannelInfo* info = &_rgChannelInfo[mappedChannel];
_rgAttitudeRadioWidget[i]->setEnabled(true);
_rgAttitudeRadioWidget[i]->setValueAndRange(_rcRawValue[mappedChannel], info->rcMin, info->rcMax);
} else {
_rgAttitudeRadioWidget[i]->setEnabled(false);
}
}
// Update the available channels
for (int chan=0; chan<_chanCount; chan++) {
_rgRadioWidget[chan]->setEnabled(true);
struct ChannelInfo* info = &_rgChannelInfo[chan];
_rgRadioWidget[chan]->setValueAndRange(_rcRawValue[chan], info->rcMin, info->rcMax);
_rgRadioWidget[chan]->setValueAndMinMax(_rcRawValue[chan], info->rcMin, info->rcMax);
_rgRadioWidget[chan]->setTrim(info->rcTrim);
}
// Disable non-available channels
......@@ -408,7 +478,6 @@ void PX4RCCalibration::_updateView()
_rgRadioWidget[chan]->setEnabled(false);
}
// FIXME: Could save some CPU by not doing this on every update
// Update the channel names for all channels
for (int chan=0; chan<_chanMax; chan++) {
struct ChannelInfo* info = &_rgChannelInfo[chan];
......@@ -420,7 +489,7 @@ void PX4RCCalibration::_updateView()
} else {
name = tr("%1 [Channel %2]").arg(_rgFunctionInfo[info->function].functionName).arg(oneBasedChannel);
}
_rgRadioWidget[chan]->setName(name);
_rgRadioWidget[chan]->setTitle(name);
}
}
......@@ -429,6 +498,7 @@ void PX4RCCalibration::_rcCalCancel(void)
{
_mav->endRadioControlCalibration();
_rcCalChannelWait(true);
_setInternalCalibrationValuesFromParameters();
}
void PX4RCCalibration::_rcCalSkip(void)
......@@ -482,7 +552,6 @@ void PX4RCCalibration::_rcCalNext(void)
break;
case rcCalStateTrims:
_copyAndSetTrims();
_rcCalSave();
break;
......@@ -504,15 +573,26 @@ void PX4RCCalibration::_rcCalChannelWait(bool firstTime)
_rcCalState = rcCalStateChannelWait;
_resetInternalCalibrationValues();
if (_chanCount == 0) {
_ui->rcCalFound->setText(tr("Please turn on Radio"));
_ui->rcCalNext->setEnabled(false);
} else {
if (_chanCount >= _chanMinimum) {
_ui->rcCalNext->setEnabled(true);
_ui->rcCalStatus->setText(tr("Detected %1 radio channels.").arg(_chanCount));
} else if (_chanCount < _chanMinimum) {
_ui->rcCalNext->setEnabled(false);
_ui->rcCalStatus->setText(tr("Detected %1 radio channels. To operate PX4, you need at least %2 channels.").arg(_chanCount).arg(_chanMinimum));
}
}
_ui->rcCalStatus->setText(tr("Please turn on Radio."));
if (firstTime) {
_ui->rcCalFound->clear();
} else {
_ui->rcCalFound->setText(tr("Calibration complete"));
}
_ui->rcCalNext->setEnabled(false);
_ui->rcCalNext->setText(tr("Start"));
_ui->rcCalCancel->setEnabled(false);
_ui->rcCalSkip->setEnabled(false);
......@@ -526,6 +606,8 @@ void PX4RCCalibration::_rcCalBegin(void)
_rcCalState = rcCalStateBegin;
_resetInternalCalibrationValues();
// Let the mav known we are starting calibration. This should turn off motors and so forth.
// FIXME: XXX magic number: Set to 1 for radio input disable
_mav->startRadioControlCalibration(1);
......@@ -535,6 +617,7 @@ void PX4RCCalibration::_rcCalBegin(void)
_ui->rcCalStatus->setText(tr("Starting RC calibration.\n\n"
"Ensure RC transmitter and receiver are powered and connected. It is recommended to disconnect all motors for additional safety, however, the system is designed to not arm during the calibration.\n\n"
"Reset all transmitter trims to center, then click Next to continue"));
_ui->rcCalFound->clear();
}
/// @brief Saves the current channel values, so that we can detect when the use moves an input.
......@@ -591,7 +674,6 @@ void PX4RCCalibration::_rcCalReadChannelsMinMax(void)
_ui->rcCalSkip->setEnabled(false);
_ui->rcCalCancel->setEnabled(true);
// Turn on min/max display for all radio widgets
_showMinMaxOnRadioWidgets(true);
}
......@@ -658,30 +740,16 @@ void PX4RCCalibration::_rcCalTrims(void)
_ui->rcCalTryAgain->setEnabled(false);
_ui->rcCalSkip->setEnabled(false);
_ui->rcCalCancel->setEnabled(true);
_initializeTrims();
_showTrimOnRadioWidgets(true);
}
/// @brief Copies the current rc values as trim positions.
void PX4RCCalibration::_copyAndSetTrims(void)
/// @brief Initializes the trim values based on current min/max.
void PX4RCCalibration::_initializeTrims(void)
{
// For the Attitude Functions we use the current RC values as the trim setting
for (int chanFunction=rcCalFunctionFirstAttitudeFunction; chanFunction<=rcCalFunctionLastAttitudeFunction; chanFunction++) {
int mappedChannel = _rgFunctionChannelMapping[chanFunction];
// All Attitude Functions should be mapped
Q_ASSERT(mappedChannel != rcCalFunctionMax);
_rgChannelInfo[mappedChannel].rcTrim = _rcRawValue[mappedChannel];
//qDebug() << "Setting Attitude Function trim: function" << chanFunction << "mapped channel" << mappedChannel << "trim" << _rgChannelInfo[mappedChannel].rcTrim;
}
// For mapped non-Attitude Funtions the trim is calculated from the min/max values
for (int chanFunction=rcCalFunctionFirstNonAttitudeFunction; chanFunction<=rcCalFunctionLastNonAttitudeFunction; chanFunction++) {
int mappedChannel = _rgFunctionChannelMapping[chanFunction];
if (mappedChannel != rcCalFunctionMax) {
_rgChannelInfo[mappedChannel].rcTrim = ((_rgChannelInfo[mappedChannel].rcMax - _rgChannelInfo[mappedChannel].rcMin) / 2.0f) + _rgChannelInfo[mappedChannel].rcMin;
//qDebug() << "Setting non-Attitude Function trim: function" << chanFunction << "mapped channel" << mappedChannel << "trim" << _rgChannelInfo[mappedChannel].rcTrim;
}
for (int chan=0; chan<=_chanMax; chan++) {
_rgChannelInfo[chan].rcTrim = ((_rgChannelInfo[chan].rcMax - _rgChannelInfo[chan].rcMin) / 2.0f) + _rgChannelInfo[chan].rcMin;
}
}
......@@ -744,18 +812,32 @@ void PX4RCCalibration::_unitTestForceCalState(enum rcCalStates state) {
void PX4RCCalibration::_showMinMaxOnRadioWidgets(bool show)
{
// Turn on min/max display for all radio widgets
Q_ASSERT(rcCalFunctionFirstAttitudeFunction == 0);
for (int i=0; i<=rcCalFunctionLastAttitudeFunction; i++) {
QGCRadioChannelDisplay* radioWidget = _rgAttitudeRadioWidget[i];
for (int i=0; i<_chanMax; i++) {
RCChannelWidget* radioWidget = _rgRadioWidget[i];
Q_ASSERT(radioWidget);
radioWidget->showMinMax(show);
}
}
/// @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++) {
QGCRadioChannelDisplay* radioWidget = _rgRadioWidget[i];
RCChannelWidget* radioWidget = _rgRadioWidget[i];
Q_ASSERT(radioWidget);
radioWidget->showMinMax(show);
radioWidget->showTrim(show);
}
}
void PX4RCCalibration::_parameterListUpToDate(void)
{
_parameterListUpToDateSignalled = true;
if (_rcCalState == rcCalStateChannelWait) {
_setInternalCalibrationValuesFromParameters();
}
}
......@@ -65,6 +65,8 @@ private slots:
void _setActiveUAS(UASInterface* uas);
void _toggleSpektrumPairing(bool enabled);
void _parameterListUpToDate(void);
private:
/// @brief These identify the various controls functions. They are also used as indices into the _rgFunctioInfo
/// aray.
......@@ -124,7 +126,8 @@ private:
void _writeCalibration(bool trimsOnly);
void _resetInternalCalibrationValues(void);
void _copyAndSetTrims(void);
void _setInternalCalibrationValuesFromParameters(void);
void _initializeTrims(void);
void _rcCalChannelWait(bool firstTime);
void _rcCalBegin(void);
......@@ -138,6 +141,7 @@ private:
void _rcCalSaveCurrentValues(void);
void _showMinMaxOnRadioWidgets(bool show);
void _showTrimOnRadioWidgets(bool show);
void _unitTestForceCalState(enum rcCalStates state);
......@@ -171,10 +175,12 @@ private:
float _rcRawValue[_chanMax]; ///< Current set of raw channel values
QGCRadioChannelDisplay* _rgAttitudeRadioWidget[4]; ///< Array of Attitide Function radio channel widgets
QGCRadioChannelDisplay* _rgRadioWidget[_chanMax]; ///< Array of radio channel widgets
RCChannelWidget* _rgRadioWidget[_chanMax]; ///< Array of radio channel widgets
UASInterface* _mav; ///< The current MAV
QGCUASParamManagerInterface* _paramMgr;
bool _parameterListUpToDateSignalled; ///< true: we have received a parameterListUpToDate signal
Ui::PX4RCCalibration* _ui;
......
......@@ -6,469 +6,495 @@
<rect>
<x>0</x>
<y>0</y>
<width>1151</width>
<height>926</height>
<width>1562</width>
<height>1286</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="0">
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0" columnstretch="0,0,0">
<item row="0" column="1">
<widget class="QGCRadioChannelDisplay" name="throttleWidget" native="true">
<property name="minimumSize">
<size>
<width>50</width>
<height>200</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>50</width>
<height>200</height>
</size>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QGCRadioChannelDisplay" name="yawWidget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QGCRadioChannelDisplay" name="pitchWidget" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>1</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>200</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>50</width>
<height>200</height>
</size>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QGCRadioChannelDisplay" name="rollWidget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item row="0" column="0">
<layout class="QVBoxLayout" name="verticalLayout_9">
<item>
<widget class="QPushButton" name="rcCopyTrimButton">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Copy the trim values from roll / pitch / yaw from manual flight to the autonomous flight modes.</string>
</property>
<property name="text">
<string>Copy Attitude Trims</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="rcCalStatus">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="rcCalFound">
<property name="text">
<string>TextLabel</string>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<widget class="QWidget" name="verticalLayoutWidget">
<property name="geometry">
<rect>
<x>760</x>
<y>0</y>
<width>252</width>
<height>715</height>
</rect>
</property>
<layout class="QVBoxLayout" name="channelGroup10to18">
<item>
<widget class="RCChannelWidget" name="radio10Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio11Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio12Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio13Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio14Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio15Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio16Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio17Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio18Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="layoutWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>486</width>
<height>525</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout" rowstretch="0" columnstretch="0">
<item row="0" column="0">
<layout class="QVBoxLayout" name="verticalLayout_9">
<item>
<widget class="QPushButton" name="rcCopyTrimButton">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Copy the trim values from roll / pitch / yaw from manual flight to the autonomous flight modes.</string>
</property>
<property name="text">
<string>Copy Attitude Trims</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="rcCalStatus">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>180</height>
</size>
</property>
<property name="text">
<string>Please turn on Radio</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="rcCalFound">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>400</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>TextLabel</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QPushButton" name="rcCalTryAgain">
<property name="text">
<string>Try Again</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="rcCalSkip">
<property name="text">
<string>Skip</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="rcCalCancel">
<property name="text">
<string>Cancel</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="rcCalNext">
<property name="text">
<string>Next</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>60</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>Spektrum RC</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_10">
<item>
<widget class="QPushButton" name="rcCalTryAgain">
<widget class="QPushButton" name="spektrumPairButton">
<property name="text">
<string>Try Again</string>
<string>Pair Receiver</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="rcCalSkip">
<widget class="QRadioButton" name="dsm2RadioButton">
<property name="text">
<string>Skip</string>
<string>DSM2 Mode</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="rcCalCancel">
<widget class="QRadioButton" name="dsmxRadioButton">
<property name="text">
<string>Cancel</string>
<string>DSMX Mode (3 to 7 channels)</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="rcCalNext">
<widget class="QRadioButton" name="dsmx8RadioButton">
<property name="text">
<string>Next</string>
<string>DSMX Mode (8 or more channels)</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>Spektrum RC</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_10">
<item>
<widget class="QPushButton" name="spektrumPairButton">
<property name="text">
<string>Pair Receiver</string>
</property>
</widget>
</item>
<item>
<widget class="QRadioButton" name="dsm2RadioButton">
<property name="text">
<string>DSM2 Mode</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QRadioButton" name="dsmxRadioButton">
<property name="text">
<string>DSMX Mode (3 to 7 channels)</string>
</property>
</widget>
</item>
<item>
<widget class="QRadioButton" name="dsmx8RadioButton">
<property name="text">
<string>DSMX Mode (8 or more channels)</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item row="0" column="1" rowspan="2">
<layout class="QVBoxLayout" name="verticalLayout_6">
<item>
<widget class="QGCRadioChannelDisplay" name="radio1Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio2Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio3Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio4Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio5Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio6Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio7Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio8Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio9Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio10Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio11Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio12Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio13Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio14Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio15Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio16Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio17Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGCRadioChannelDisplay" name="radio18Widget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
<height>40</height>
</size>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_4">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item row="1" column="0">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<widget class="QWidget" name="layoutWidget">
<property name="geometry">
<rect>
<x>490</x>
<y>0</y>
<width>252</width>
<height>715</height>
</rect>
</property>
<layout class="QVBoxLayout" name="channelGroup1to9" stretch="0,0,0,0,0,0,0,0,0">
<item>
<widget class="RCChannelWidget" name="radio1Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio2Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio3Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio4Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio5Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio6Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio7Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio8Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="RCChannelWidget" name="radio9Widget">
<property name="minimumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>65</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
</widget>
<customwidgets>
<customwidget>
<class>QGCRadioChannelDisplay</class>
<extends>QWidget</extends>
<header>ui/designer/QGCRadioChannelDisplay.h</header>
<class>RCChannelWidget</class>
<extends>QGroupBox</extends>
<header>ui/designer/RCChannelWidget.h</header>
<container>1</container>
</customwidget>
</customwidgets>
......
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