Commit e6aaf9c6 authored by Don Gagne's avatar Don Gagne

Merge pull request #1075 from DonLakeFlyer/FlightModeSetup

Flight mode setup
parents a709b2f9 9991c153
...@@ -282,7 +282,7 @@ FORMS += \ ...@@ -282,7 +282,7 @@ FORMS += \
src/ui/designer/QGCParamSlider.ui \ src/ui/designer/QGCParamSlider.ui \
src/ui/designer/QGCActionButton.ui \ src/ui/designer/QGCActionButton.ui \
src/ui/designer/QGCCommandButton.ui \ src/ui/designer/QGCCommandButton.ui \
src/ui/designer/QGCComboBox.ui \ src/ui/designer/QGCToolWidgetComboBox.ui \
src/ui/designer/QGCTextLabel.ui \ src/ui/designer/QGCTextLabel.ui \
src/ui/designer/QGCXYPlot.ui \ src/ui/designer/QGCXYPlot.ui \
src/ui/QGCMAVLinkLogPlayer.ui \ src/ui/QGCMAVLinkLogPlayer.ui \
...@@ -391,7 +391,7 @@ HEADERS += \ ...@@ -391,7 +391,7 @@ HEADERS += \
src/ui/designer/QGCParamSlider.h \ src/ui/designer/QGCParamSlider.h \
src/ui/designer/QGCCommandButton.h \ src/ui/designer/QGCCommandButton.h \
src/ui/designer/QGCToolWidgetItem.h \ src/ui/designer/QGCToolWidgetItem.h \
src/ui/designer/QGCComboBox.h \ src/ui/designer/QGCToolWidgetComboBox.h \
src/ui/designer/QGCTextLabel.h \ src/ui/designer/QGCTextLabel.h \
src/ui/designer/QGCRadioChannelDisplay.h \ src/ui/designer/QGCRadioChannelDisplay.h \
src/ui/designer/QGCXYPlot.h \ src/ui/designer/QGCXYPlot.h \
...@@ -477,7 +477,8 @@ HEADERS += \ ...@@ -477,7 +477,8 @@ HEADERS += \
src/CmdLineOptParser.h \ src/CmdLineOptParser.h \
src/uas/QGXPX4UAS.h \ src/uas/QGXPX4UAS.h \
src/QGCFileDialog.h \ src/QGCFileDialog.h \
src/QGCMessageBox.h src/QGCMessageBox.h \
src/QGCComboBox.h
SOURCES += \ SOURCES += \
src/main.cc \ src/main.cc \
...@@ -533,7 +534,7 @@ SOURCES += \ ...@@ -533,7 +534,7 @@ SOURCES += \
src/ui/designer/QGCParamSlider.cc \ src/ui/designer/QGCParamSlider.cc \
src/ui/designer/QGCCommandButton.cc \ src/ui/designer/QGCCommandButton.cc \
src/ui/designer/QGCToolWidgetItem.cc \ src/ui/designer/QGCToolWidgetItem.cc \
src/ui/designer/QGCComboBox.cc \ src/ui/designer/QGCToolWidgetComboBox.cc \
src/ui/designer/QGCTextLabel.cc \ src/ui/designer/QGCTextLabel.cc \
src/ui/designer/QGCRadioChannelDisplay.cpp \ src/ui/designer/QGCRadioChannelDisplay.cpp \
src/ui/designer/QGCXYPlot.cc \ src/ui/designer/QGCXYPlot.cc \
...@@ -614,8 +615,8 @@ SOURCES += \ ...@@ -614,8 +615,8 @@ SOURCES += \
src/uas/QGCUASWorker.cc \ src/uas/QGCUASWorker.cc \
src/CmdLineOptParser.cc \ src/CmdLineOptParser.cc \
src/uas/QGXPX4UAS.cc \ src/uas/QGXPX4UAS.cc \
src/QGCFileDialog.cc src/QGCFileDialog.cc \
src/QGCComboBox.cc
# #
# Unit Test specific configuration goes here # Unit Test specific configuration goes here
...@@ -652,7 +653,8 @@ HEADERS += \ ...@@ -652,7 +653,8 @@ HEADERS += \
src/qgcunittest/QGCUASFileManagerTest.h \ src/qgcunittest/QGCUASFileManagerTest.h \
src/qgcunittest/PX4RCCalibrationTest.h \ src/qgcunittest/PX4RCCalibrationTest.h \
src/qgcunittest/LinkManagerTest.h \ src/qgcunittest/LinkManagerTest.h \
src/qgcunittest/MainWindowTest.h src/qgcunittest/MainWindowTest.h \
src/AutoPilotPlugins/PX4/Tests/FlightModeConfigTest.h
SOURCES += \ SOURCES += \
src/qgcunittest/UnitTest.cc \ src/qgcunittest/UnitTest.cc \
...@@ -672,7 +674,8 @@ SOURCES += \ ...@@ -672,7 +674,8 @@ SOURCES += \
src/qgcunittest/QGCUASFileManagerTest.cc \ src/qgcunittest/QGCUASFileManagerTest.cc \
src/qgcunittest/PX4RCCalibrationTest.cc \ src/qgcunittest/PX4RCCalibrationTest.cc \
src/qgcunittest/LinkManagerTest.cc \ src/qgcunittest/LinkManagerTest.cc \
src/qgcunittest/MainWindowTest.cc src/qgcunittest/MainWindowTest.cc \
src/AutoPilotPlugins/PX4/Tests/FlightModeConfigTest.cc
} }
# #
...@@ -682,7 +685,8 @@ FORMS += \ ...@@ -682,7 +685,8 @@ FORMS += \
src/VehicleSetup/SetupView.ui \ src/VehicleSetup/SetupView.ui \
src/VehicleSetup/SummaryPage.ui \ src/VehicleSetup/SummaryPage.ui \
src/VehicleSetup/ParameterEditor.ui \ src/VehicleSetup/ParameterEditor.ui \
src/ui/QGCPX4VehicleConfig.ui src/ui/QGCPX4VehicleConfig.ui \
src/AutoPilotPlugins/PX4/FlightModeConfig.ui
HEADERS+= \ HEADERS+= \
src/VehicleSetup/SetupView.h \ src/VehicleSetup/SetupView.h \
...@@ -698,6 +702,7 @@ HEADERS+= \ ...@@ -698,6 +702,7 @@ HEADERS+= \
src/AutoPilotPlugins/PX4/PX4Component.h \ src/AutoPilotPlugins/PX4/PX4Component.h \
src/AutoPilotPlugins/PX4/RadioComponent.h \ src/AutoPilotPlugins/PX4/RadioComponent.h \
src/AutoPilotPlugins/PX4/FlightModesComponent.h \ src/AutoPilotPlugins/PX4/FlightModesComponent.h \
src/AutoPilotPlugins/PX4/FlightModeConfig.h \
src/AutoPilotPlugins/PX4/AirframeComponent.h \ src/AutoPilotPlugins/PX4/AirframeComponent.h \
src/AutoPilotPlugins/PX4/SensorsComponent.h src/AutoPilotPlugins/PX4/SensorsComponent.h
...@@ -712,5 +717,6 @@ SOURCES += \ ...@@ -712,5 +717,6 @@ SOURCES += \
src/AutoPilotPlugins/PX4/PX4Component.cc \ src/AutoPilotPlugins/PX4/PX4Component.cc \
src/AutoPilotPlugins/PX4/RadioComponent.cc \ src/AutoPilotPlugins/PX4/RadioComponent.cc \
src/AutoPilotPlugins/PX4/FlightModesComponent.cc \ src/AutoPilotPlugins/PX4/FlightModesComponent.cc \
src/AutoPilotPlugins/PX4/FlightModeConfig.cc \
src/AutoPilotPlugins/PX4/AirframeComponent.cc \ src/AutoPilotPlugins/PX4/AirframeComponent.cc \
src/AutoPilotPlugins/PX4/SensorsComponent.cc src/AutoPilotPlugins/PX4/SensorsComponent.cc
[Rules]
*Log=false
/*=====================================================================
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 Flight Mode Configuration
/// @author Don Gagne <don@thegagnes.com
#include "FlightModeConfig.h"
#include "UASManager.h"
#include "QGCMessageBox.h"
const char* FlightModeConfig::_modeSwitchParam = "RC_MAP_MODE_SW";
const char* FlightModeConfig::_manualSwitchParam = "RC_MAP_ACRO_SW";
const char* FlightModeConfig::_assistSwitchParam = "RC_MAP_POSCTL_SW";
const char* FlightModeConfig::_returnSwitchParam = "RC_MAP_RETURN_SW";
const char* FlightModeConfig::_loiterSwitchParam = "RC_MAP_LOITER_SW";
FlightModeConfig::FlightModeConfig(QWidget *parent) :
QWidget(parent),
_mav(NULL),
_paramMgr(NULL),
_ui(new Ui::FlightModeConfig)
{
Q_CHECK_PTR(_ui);
_ui->setupUi(this);
// Expectation is that we have an active uas, it is connected and the parameters are ready
_mav = UASManager::instance()->getActiveUAS();
Q_ASSERT(_mav);
_paramMgr = _mav->getParamManager();
Q_ASSERT(_paramMgr);
Q_ASSERT(_paramMgr->parametersReady());
_componentId = _paramMgr->getDefaultComponentId();
connect(_paramMgr, SIGNAL(parameterUpdated(int, QString, QVariant)), this, SLOT(_parameterUpdated(int, QString, QVariant)));
_initUi();
}
/// @brief Intialize the UI elements
void FlightModeConfig::_initUi(void) {
struct Combo2Param {
QGCComboBox* combo;
QButtonGroup* buttonGroup;
const char* param;
const char* description;
};
struct Combo2Param rgCombo2ParamMap[] = {
{ _ui->modeSwitchChannel, _ui->modeSwitchGroup, _modeSwitchParam, "Mode Switch" },
{ _ui->manualSwitchChannel, _ui->manualSwitchGroup, _manualSwitchParam, "Manual Switch" },
{ _ui->assistSwitchChannel, _ui->assistSwitchGroup, _assistSwitchParam, "Assist Switch" },
{ _ui->returnSwitchChannel, _ui->returnSwitchGroup, _returnSwitchParam, "Return Switch" },
{ _ui->loiterSwitchChannel, _ui->loiterSwitchGroup, _loiterSwitchParam, "Loiter Switch" },
{ NULL, NULL, "RC_MAP_THROTTLE", "Throttle" },
{ NULL, NULL, "RC_MAP_YAW", "Rudder" },
{ NULL, NULL, "RC_MAP_ROLL", "Aileron" },
{ NULL, NULL, "RC_MAP_PITCH", "Elevator" },
{ NULL, NULL, "RC_MAP_AUX1", "Aux1" },
{ NULL, NULL, "RC_MAP_AUX2", "Aux2" },
{ NULL, NULL, "RC_MAP_AUX3", "Aux3" }
};
// Setup up maps
for (size_t i=0; i<sizeof(rgCombo2ParamMap)/sizeof(rgCombo2ParamMap[0]); i++) {
struct Combo2Param* map = &rgCombo2ParamMap[i];
if (map->combo) {
Q_ASSERT(!_mapChannelCombo2Param.contains(map->combo));
_mapChannelCombo2Param[map->combo] = map->param;
Q_ASSERT(!_mapChannelCombo2ButtonGroup.contains(map->combo));
_mapChannelCombo2ButtonGroup[map->combo] = map->buttonGroup;
// We connect to activated because we only want signals from user initiated changes
connect(map->combo, SIGNAL(activated(int)), this, SLOT(_channelSelected(int)));
}
Q_ASSERT(!_mapParam2FunctionInfo.contains(map->param));
_mapParam2FunctionInfo[map->param] = map->description;
}
_updateAllSwitches();
// Finally if RC Calibration has not been performed disable the entire widget and inform user
if (_getChannelMapForParam(_modeSwitchParam) == 0) {
// FIXME: Do something more than disable
setEnabled(false);
}
}
void FlightModeConfig::_updateAllSwitches(void)
{
foreach(QGCComboBox* combo, _mapChannelCombo2Param.keys()) {
_updateSwitchUiGroup(combo);
}
}
/// @brief Selects the channel in the combo for the given parameter
void FlightModeConfig::_selectChannelForParam(QGCComboBox* combo, const QString& parameter)
{
int channel = _getChannelMapForParam(parameter);
int index = combo->findData(channel);
Q_ASSERT(index != -1);
combo->setCurrentIndex(index);
}
/// @brief Fills a channel selection combo box with channel values
void FlightModeConfig::_updateSwitchUiGroup(QGCComboBox* combo)
{
QMap<int, QString> mapChannelUsed2Description;
// Make a map of all channels currently mapped
foreach(QString paramId, _mapParam2FunctionInfo.keys()) {
int channel = _getChannelMapForParam(paramId);
if (channel != 0) {
mapChannelUsed2Description[channel] = _mapParam2FunctionInfo[paramId];
}
}
combo->clear();
combo->addItem("Disabled", 0);
for (int i=1; i<=_maxChannels; i++) {
QString comboText = QString("Channel %1").arg(i);
if (mapChannelUsed2Description.contains(i)) {
comboText += QString(" (%1)").arg(mapChannelUsed2Description[i]);
}
combo->addItem(comboText, i);
}
_selectChannelForParam(combo, _mapChannelCombo2Param[combo]);
// Enable/Disable radio buttons appropriately
int channelMap = _getChannelMapForParam(_mapChannelCombo2Param[combo]);
Q_ASSERT(_mapChannelCombo2ButtonGroup.contains(combo));
Q_ASSERT(_mapChannelCombo2ButtonGroup[combo]->buttons().count() > 0);
foreach(QAbstractButton* button, _mapChannelCombo2ButtonGroup[combo]->buttons()) {
QRadioButton* radio = qobject_cast<QRadioButton*>(button);
Q_ASSERT(radio);
radio->setEnabled(channelMap != 0);
}
}
/// @brief Returns channel mapping for the specified parameters
int FlightModeConfig::_getChannelMapForParam(const QString& paramId)
{
QVariant value;
bool found = _paramMgr->getParameterValue(_componentId, paramId, value);
Q_UNUSED(found);
Q_ASSERT(found);
bool conversionOk;
int channel = value.toInt(&conversionOk);
Q_UNUSED(conversionOk);
Q_ASSERT(conversionOk);
return channel;
}
/// @brief Called when a selection occurs in one of the channel combo boxes
void FlightModeConfig::_channelSelected(int requestedMapping)
{
QGCComboBox* combo = qobject_cast<QGCComboBox*>(sender());
Q_ASSERT(combo);
Q_ASSERT(_mapChannelCombo2Param.contains(combo));
// Check for no-op
int currentMapping = _getChannelMapForParam(_mapChannelCombo2Param[combo]);
if (currentMapping == requestedMapping) {
return;
}
// Make sure that channel is not already mapped
if (requestedMapping == 0) {
// Channel was disabled
if (combo == _ui->modeSwitchChannel) {
// Mode switch is not allowed to be disabled.
QGCMessageBox::warning(tr("Flight Mode"), "Mode Switch is a required switch and cannot be disabled.");
_selectChannelForParam(combo, _mapChannelCombo2Param[combo]);
return;
}
} else {
// Channel was remapped to a non-disabled channel
foreach(QString paramId, _mapParam2FunctionInfo.keys()) {
int usedChannelMap = _getChannelMapForParam(paramId);
if (requestedMapping == usedChannelMap) {
QGCMessageBox::warning(tr("Flight Mode"), "You cannot use a channel which is already mapped.");
_selectChannelForParam(combo, _mapChannelCombo2Param[combo]);
return;
}
}
}
// Save the new setting to the parameter
_paramMgr->setParameter(_componentId, _mapChannelCombo2Param[combo], requestedMapping);
_paramMgr->sendPendingParameters(true, false);
}
void FlightModeConfig::_parameterUpdated(int componentId, QString parameter, QVariant value)
{
Q_UNUSED(componentId);
Q_UNUSED(value);
// If this is a function mapping parameter update the combos
if (_mapParam2FunctionInfo.contains(parameter)) {
_updateAllSwitches();
}
// Finally if RC Calibration suddenly needs to be re-done disable the entire widget and inform user
if (parameter == _modeSwitchParam) {
// FIXME: Do something more than disable
if (isEnabled() == false && value.toInt() != 0) {
setEnabled(true);
} else if (isEnabled() == true && value.toInt() == 0) {
setEnabled(false);
}
}
}
\ No newline at end of file
/*=====================================================================
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 Flight Mode Configuration
/// @author Don Gagne <don@thegagnes.com
#ifndef FlightModeConfig_H
#define FlightModeConfig_H
#include <QWidget>
#include "UASInterface.h"
#include "ui_FlightModeConfig.h"
namespace Ui {
class FlightModeConfig;
}
class FlightModeConfig : public QWidget
{
Q_OBJECT
friend class FlightModeConfigTest; ///< This allows our unit test to access internal information needed.
public:
explicit FlightModeConfig(QWidget *parent = 0);
private slots:
void _channelSelected(int index);
void _parameterUpdated(int componentId, QString parameter, QVariant value);
private:
void _initUi(void);
void _updateSwitchUiGroup(QGCComboBox* combo);
void _selectChannelForParam(QGCComboBox* combo, const QString& parameter);
void _updateAllSwitches(void);
int _getChannelMapForParam(const QString& parameter);
UASInterface* _mav; ///< The current MAV
int _componentId; ///< Default component id
QGCUASParamManagerInterface* _paramMgr;
static const int _maxChannels = 18;
QMap<QGCComboBox*, QString> _mapChannelCombo2Param;
QMap<QGCComboBox*, QButtonGroup*> _mapChannelCombo2ButtonGroup;
QMap<QString, QString> _mapParam2FunctionInfo;
static const char* _modeSwitchParam;
static const char* _manualSwitchParam;
static const char* _assistSwitchParam;
static const char* _returnSwitchParam;
static const char* _loiterSwitchParam;
Ui::FlightModeConfig* _ui;
};
#endif
This diff is collapsed.
...@@ -25,9 +25,7 @@ ...@@ -25,9 +25,7 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "FlightModesComponent.h" #include "FlightModesComponent.h"
#include "FlightModeConfig.h"
#include <QVBoxLayout>
#include <QLabel>
/// @brief Parameters which signal a change in setupComplete state /// @brief Parameters which signal a change in setupComplete state
static const char* triggerParams[] = { "RC_MAP_MODE_SW", NULL }; static const char* triggerParams[] = { "RC_MAP_MODE_SW", NULL };
...@@ -115,13 +113,7 @@ QStringList FlightModesComponent::paramFilterList(void) const ...@@ -115,13 +113,7 @@ QStringList FlightModesComponent::paramFilterList(void) const
QWidget* FlightModesComponent::setupWidget(void) const QWidget* FlightModesComponent::setupWidget(void) const
{ {
QWidget* widget = new QWidget; return new FlightModeConfig();
QVBoxLayout* layout = new QVBoxLayout(widget);
QLabel* label = new QLabel("Coming Soon\nUse Radio setup for Main Mode Switch setup\n(Use Flight Modes Parameters for everything else)", widget);
label->setAlignment(Qt::AlignHCenter | Qt::AlignVCenter);
layout->addWidget(label);
return widget;
} }
QList<QStringList> FlightModesComponent::summaryItems(void) const QList<QStringList> FlightModesComponent::summaryItems(void) const
......
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/>.
======================================================================*/
#ifndef FlightModeConfigTest_H
#define FlightModeConfigTest_H
#include "UnitTest.h"
#include "MockUASManager.h"
#include "MockUAS.h"
#include "AutoPilotPlugins/PX4/FlightModeConfig.h"
/// @file
/// @brief FlightModeConfig Widget unit test
///
/// @author Don Gagne <don@thegagnes.com>
class FlightModeConfigTest : public UnitTest
{
Q_OBJECT
public:
FlightModeConfigTest(void);
private slots:
void initTestCase(void);
void init(void);
void cleanup(void);
void _create_test(void);
void _validateInitialState_test(void);
void _validateRCCalCheck_test(void);
void _attempChannelReuse_test(void);
void _validateRadioButtonEnableDisable_test(void);
void _validateModeSwitchMustBeEnabled_test(void);
private:
int _getChannelMapForParam(const QString& parameter);
MockUASManager* _mockUASManager;
MockUAS* _mockUAS;
QGCUASParamManagerInterface* _paramMgr;
FlightModeConfig* _configWidget;
int _defaultComponentId;
QMap<QGCComboBox*, QString> _mapChannelCombo2Param;
QMap<QGCComboBox*, QButtonGroup*> _mapChannelCombo2ButtonGroup;
static const int _availableChannels = 18; ///< Simulate 18 channel RC Transmitter
};
#endif
/*=====================================================================
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 Subclass of QComboBox. Mainly used for unit test so you can simulate a user selection
/// with correct signalling.
///
/// @author Don Gagne <don@thegagnes.com>
#include "QGCComboBox.h"
QGCComboBox::QGCComboBox(QWidget* parent) :
QComboBox(parent)
{
}
void QGCComboBox::simulateUserSetCurrentIndex(int index)
{
Q_ASSERT(index >=0 && index < count());
// This will signal currentIndexChanged
setCurrentIndex(index);
// We have to manually signal activated
emit activated(index);
emit activated(itemText(index));
}
/*=====================================================================
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/>.
======================================================================*/
#ifndef QGCComboBox_H
#define QGCComboBox_H
#include <QComboBox>
/// @file
/// @brief Subclass of QComboBox. Mainly used for unit test so you can simulate a user selection
/// with correct signalling.
///
/// @author Don Gagne <don@thegagnes.com>
class QGCComboBox : public QComboBox {
Q_OBJECT
public:
QGCComboBox(QWidget* parent = NULL);
/// @brief Sets the current index on the combo. Signals activated, as well as currentIndexChanged.
void simulateUserSetCurrentIndex(int index);
};
#endif
...@@ -22,12 +22,16 @@ ...@@ -22,12 +22,16 @@
======================================================================*/ ======================================================================*/
#include "MockQGCUASParamManager.h" #include "MockQGCUASParamManager.h"
#include "mavlink.h"
#include <QTest> #include <QTest>
#include <QDebug> #include <QDebug>
Q_LOGGING_CATEGORY(MockQGCUASParamManagerLog, "MockQGCUASParamManagerLog")
MockQGCUASParamManager::MockQGCUASParamManager(void) MockQGCUASParamManager::MockQGCUASParamManager(void)
{ {
_loadParams();
} }
bool MockQGCUASParamManager::getParameterValue(int component, const QString& parameter, QVariant& value) const bool MockQGCUASParamManager::getParameterValue(int component, const QString& parameter, QVariant& value) const
...@@ -36,13 +40,65 @@ bool MockQGCUASParamManager::getParameterValue(int component, const QString& par ...@@ -36,13 +40,65 @@ bool MockQGCUASParamManager::getParameterValue(int component, const QString& par
if (_mapParams.contains(parameter)) { if (_mapParams.contains(parameter)) {
value = _mapParams[parameter]; value = _mapParams[parameter];
return true;
} }
qCDebug(MockQGCUASParamManagerLog) << QString("getParameterValue: parameter not found %1").arg(parameter);
return false; return false;
} }
void MockQGCUASParamManager::setParameter(int component, QString parameterName, QVariant value) void MockQGCUASParamManager::setParameter(int component, QString parameterName, QVariant value)
{ {
Q_UNUSED(component); qCDebug(MockQGCUASParamManagerLog) << QString("setParameter: component(%1) parameter(%2) value(%3)").arg(component).arg(parameterName).arg(value.toString());
_mapParams[parameterName] = value;
emit parameterUpdated(_defaultComponentId, parameterName, value);
}
_mapParamsSet[parameterName] = value; void MockQGCUASParamManager::_loadParams(void)
{
QFile paramFile(":/unittest/MockLink.param");
bool success = paramFile.open(QFile::ReadOnly);
Q_UNUSED(success);
Q_ASSERT(success);
QTextStream paramStream(&paramFile);
while (!paramStream.atEnd()) {
QString line = paramStream.readLine();
if (line.startsWith("#")) {
continue;
}
QStringList paramData = line.split("\t");
Q_ASSERT(paramData.count() == 5);
QString paramName = paramData.at(2);
QString valStr = paramData.at(3);
uint paramType = paramData.at(4).toUInt();
QVariant paramValue;
switch (paramType) {
case MAV_PARAM_TYPE_REAL32:
paramValue = QVariant(valStr.toFloat());
break;
case MAV_PARAM_TYPE_UINT32:
paramValue = QVariant(valStr.toUInt());
break;
case MAV_PARAM_TYPE_INT32:
paramValue = QVariant(valStr.toInt());
break;
case MAV_PARAM_TYPE_INT8:
paramValue = QVariant((unsigned char)valStr.toUInt());
break;
default:
Q_ASSERT(false);
break;
}
Q_ASSERT(!_mapParams.contains(paramName));
_mapParams[paramName] = paramValue;
}
} }
...@@ -24,8 +24,12 @@ ...@@ -24,8 +24,12 @@
#ifndef MOCKQGCUASPARAMMANAGER_H #ifndef MOCKQGCUASPARAMMANAGER_H
#define MOCKQGCUASPARAMMANAGER_H #define MOCKQGCUASPARAMMANAGER_H
#include <QLoggingCategory>
#include "QGCUASParamManagerInterface.h" #include "QGCUASParamManagerInterface.h"
Q_DECLARE_LOGGING_CATEGORY(MockQGCUASParamManagerLog)
/// @file /// @file
/// @brief This is a mock implementation of QGCUASParamManager for writing Unit Tests. /// @brief This is a mock implementation of QGCUASParamManager for writing Unit Tests.
/// ///
...@@ -39,11 +43,12 @@ class MockQGCUASParamManager : public QGCUASParamManagerInterface ...@@ -39,11 +43,12 @@ class MockQGCUASParamManager : public QGCUASParamManagerInterface
signals: signals:
// The following QGCSUASParamManagerInterface signals are supported // The following QGCSUASParamManagerInterface signals are supported
void parameterListUpToDate(); // You can connect to this signal, but it will never be emitted void parameterListUpToDate(); // You can connect to this signal, but it will never be emitted
void parameterUpdated(int compId, QString paramName, QVariant value);
public: public:
// Implemented QGCSUASParamManager overrides // Implemented QGCSUASParamManager overrides
virtual bool getParameterValue(int component, const QString& parameter, QVariant& value) const; virtual bool getParameterValue(int component, const QString& parameter, QVariant& value) const;
virtual int getDefaultComponentId(void) { return 0; } virtual int getDefaultComponentId(void) { return _defaultComponentId; }
virtual int countOnboardParams(void) { return _mapParams.count(); } virtual int countOnboardParams(void) { return _mapParams.count(); }
public slots: public slots:
...@@ -53,7 +58,7 @@ public slots: ...@@ -53,7 +58,7 @@ public slots:
{ Q_UNUSED(forceSend); setParameter(componentId, key, value); } { Q_UNUSED(forceSend); setParameter(componentId, key, value); }
virtual void sendPendingParameters(bool persistAfterSend = false, bool forceSend = false) virtual void sendPendingParameters(bool persistAfterSend = false, bool forceSend = false)
{ Q_UNUSED(persistAfterSend); Q_UNUSED(forceSend); } { Q_UNUSED(persistAfterSend); Q_UNUSED(forceSend); }
virtual bool parametersReady(void) { return false; } virtual bool parametersReady(void) { return true; }
public: public:
// MockQGCUASParamManager methods // MockQGCUASParamManager methods
...@@ -66,9 +71,9 @@ public: ...@@ -66,9 +71,9 @@ public:
void setMockParameters(ParamMap_t& map) { _mapParams = map; } void setMockParameters(ParamMap_t& map) { _mapParams = map; }
/// Returns the parameters which were set by calls to setParameter calls /// Returns the parameters which were set by calls to setParameter calls
ParamMap_t getMockSetParameters(void) { return _mapParamsSet; } ParamMap_t getMockSetParameters(void) { return _mapParams; }
/// Clears the set of parameters set by setParameter calls /// Clears the set of parameters set by setParameter calls
void clearMockSetParameters(void) { _mapParamsSet.clear(); } void clearMockSetParameters(void) { _mapParams.clear(); }
public: public:
// Unimplemented QGCUASParamManagerInterface overrides // Unimplemented QGCUASParamManagerInterface overrides
...@@ -92,8 +97,11 @@ public slots: ...@@ -92,8 +97,11 @@ public slots:
virtual void copyPersistentParamsToVolatile() { Q_ASSERT(false); } virtual void copyPersistentParamsToVolatile() { Q_ASSERT(false); }
private: private:
void _loadParams(void);
ParamMap_t _mapParams; ParamMap_t _mapParams;
ParamMap_t _mapParamsSet;
static const int _defaultComponentId = 50;
// Bogus variables used for return types of NYI methods // Bogus variables used for return types of NYI methods
QList<int> _bogusQListInt; QList<int> _bogusQListInt;
......
...@@ -161,13 +161,14 @@ void PX4RCCalibrationTest::init(void) ...@@ -161,13 +161,14 @@ void PX4RCCalibrationTest::init(void)
_mockUAS = new MockUAS(); _mockUAS = new MockUAS();
Q_CHECK_PTR(_mockUAS); Q_CHECK_PTR(_mockUAS);
// This will instatiate the widget with no active UAS set _mockUASManager->setMockActiveUAS(_mockUAS);
// This will instatiate the widget with an active uas with ready parameters
_calWidget = new PX4RCCalibration(); _calWidget = new PX4RCCalibration();
Q_CHECK_PTR(_calWidget); Q_CHECK_PTR(_calWidget);
_calWidget->_setUnitTestMode(); _calWidget->_setUnitTestMode();
_calWidget->setVisible(true); _calWidget->setVisible(true);
_mockUASManager->setMockActiveUAS(_mockUAS);
// Get pointers to the push buttons // Get pointers to the push buttons
_cancelButton = _calWidget->findChild<QPushButton*>("rcCalCancel"); _cancelButton = _calWidget->findChild<QPushButton*>("rcCalCancel");
...@@ -215,17 +216,6 @@ void PX4RCCalibrationTest::cleanup(void) ...@@ -215,17 +216,6 @@ void PX4RCCalibrationTest::cleanup(void)
} }
/// @brief Tests for correct behavior when active UAS is set into widget.
void PX4RCCalibrationTest::_setUAS_test(void)
{
// Widget is initialized with UAS, so it should be enabled
QCOMPARE(_calWidget->isEnabled(), true);
// Take away the UAS and widget should disable
_mockUASManager->setMockActiveUAS(NULL);
QCOMPARE(_calWidget->isEnabled(), false);
}
/// @brief Test for correct behavior in determining minimum numbers of channels for flight. /// @brief Test for correct behavior in determining minimum numbers of channels for flight.
void PX4RCCalibrationTest::_minRCChannels_test(void) void PX4RCCalibrationTest::_minRCChannels_test(void)
{ {
......
...@@ -48,7 +48,6 @@ private slots: ...@@ -48,7 +48,6 @@ private slots:
void init(void); void init(void);
void cleanup(void); void cleanup(void);
void _setUAS_test(void);
void _minRCChannels_test(void); void _minRCChannels_test(void);
void _fullCalibration_test(void); void _fullCalibration_test(void);
......
...@@ -42,8 +42,16 @@ QGCUASFileManagerUnitTest::QGCUASFileManagerUnitTest(void) : ...@@ -42,8 +42,16 @@ QGCUASFileManagerUnitTest::QGCUASFileManagerUnitTest(void) :
// Called once before all test cases are run // Called once before all test cases are run
void QGCUASFileManagerUnitTest::initTestCase(void) void QGCUASFileManagerUnitTest::initTestCase(void)
{ {
_mockUAS.setMockSystemId(_systemIdServer); _mockUAS = new MockUAS();
_mockUAS.setMockMavlinkPlugin(&_mockFileServer); Q_CHECK_PTR(_mockUAS);
_mockUAS->setMockSystemId(_systemIdServer);
_mockUAS->setMockMavlinkPlugin(&_mockFileServer);
}
void QGCUASFileManagerUnitTest::cleanupTestCase(void)
{
delete _mockUAS;
} }
// Called before every test case // Called before every test case
...@@ -53,7 +61,7 @@ void QGCUASFileManagerUnitTest::init(void) ...@@ -53,7 +61,7 @@ void QGCUASFileManagerUnitTest::init(void)
Q_ASSERT(_multiSpy == NULL); Q_ASSERT(_multiSpy == NULL);
_fileManager = new QGCUASFileManager(NULL, &_mockUAS, _systemIdQGC); _fileManager = new QGCUASFileManager(NULL, _mockUAS, _systemIdQGC);
Q_CHECK_PTR(_fileManager); Q_CHECK_PTR(_fileManager);
// Reset any internal state back to normal // Reset any internal state back to normal
......
...@@ -48,6 +48,7 @@ public: ...@@ -48,6 +48,7 @@ public:
private slots: private slots:
// Test case initialization // Test case initialization
void initTestCase(void); void initTestCase(void);
void cleanupTestCase(void);
void init(void); void init(void);
void cleanup(void); void cleanup(void);
...@@ -84,7 +85,7 @@ private: ...@@ -84,7 +85,7 @@ private:
static const uint8_t _systemIdQGC = 255; static const uint8_t _systemIdQGC = 255;
static const uint8_t _systemIdServer = 128; static const uint8_t _systemIdServer = 128;
MockUAS _mockUAS; MockUAS* _mockUAS;
MockMavlinkFileServer _mockFileServer; MockMavlinkFileServer _mockFileServer;
QGCUASFileManager* _fileManager; QGCUASFileManager* _fileManager;
......
...@@ -10,7 +10,7 @@ ...@@ -10,7 +10,7 @@
#include <QStandardPaths> #include <QStandardPaths>
#include "QGCParamSlider.h" #include "QGCParamSlider.h"
#include "QGCComboBox.h" #include "QGCToolWidgetComboBox.h"
#include "QGCTextLabel.h" #include "QGCTextLabel.h"
#include "QGCXYPlot.h" #include "QGCXYPlot.h"
#include "QGCCommandButton.h" #include "QGCCommandButton.h"
...@@ -230,7 +230,7 @@ void QGCToolWidget::setParameterValue(int uas, int component, QString parameterN ...@@ -230,7 +230,7 @@ void QGCToolWidget::setParameterValue(int uas, int component, QString parameterN
QString checkparam = settingsMap.value(widgetName + "\\" + QString::number(j) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID").toString(); QString checkparam = settingsMap.value(widgetName + "\\" + QString::number(j) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID").toString();
if (checkparam == parameterName) if (checkparam == parameterName)
{ {
item = new QGCComboBox(this); item = new QGCToolWidgetComboBox(this);
addToolWidget(item); addToolWidget(item);
item->readSettings(widgetName + "\\" + QString::number(j) + "\\",settingsMap); item->readSettings(widgetName + "\\" + QString::number(j) + "\\",settingsMap);
paramToItemMap[parameterName] = item; paramToItemMap[parameterName] = item;
...@@ -274,7 +274,7 @@ void QGCToolWidget::loadSettings(QVariantMap& settings) ...@@ -274,7 +274,7 @@ void QGCToolWidget::loadSettings(QVariantMap& settings)
} }
else if (type == "COMBO") else if (type == "COMBO")
{ {
item = new QGCComboBox(this); item = new QGCToolWidgetComboBox(this);
//qDebug() << "CREATED COMBOBOX"; //qDebug() << "CREATED COMBOBOX";
} }
else if (type == "XYPLOT") else if (type == "XYPLOT")
...@@ -330,7 +330,7 @@ void QGCToolWidget::loadSettings(QSettings& settings) ...@@ -330,7 +330,7 @@ void QGCToolWidget::loadSettings(QSettings& settings)
} }
else if (type == "COMBO") else if (type == "COMBO")
{ {
item = new QGCComboBox(this); item = new QGCToolWidgetComboBox(this);
item->setActiveUAS(mav); item->setActiveUAS(mav);
qDebug() << "CREATED PARAM COMBOBOX"; qDebug() << "CREATED PARAM COMBOBOX";
} }
......
...@@ -5,13 +5,13 @@ ...@@ -5,13 +5,13 @@
#include <QToolTip> #include <QToolTip>
#include <QDebug> #include <QDebug>
#include "QGCComboBox.h" #include "QGCToolWidgetComboBox.h"
#include "ui_QGCComboBox.h" #include "ui_QGCToolWidgetComboBox.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "UASManager.h" #include "UASManager.h"
QGCComboBox::QGCComboBox(QWidget *parent) : QGCToolWidgetComboBox::QGCToolWidgetComboBox(QWidget *parent) :
QGCToolWidgetItem("Combo", parent), QGCToolWidgetItem("Combo", parent),
parameterName(""), parameterName(""),
parameterValue(0.0f), parameterValue(0.0f),
...@@ -19,7 +19,7 @@ QGCComboBox::QGCComboBox(QWidget *parent) : ...@@ -19,7 +19,7 @@ QGCComboBox::QGCComboBox(QWidget *parent) :
parameterMin(0.0f), parameterMin(0.0f),
parameterMax(0.0f), parameterMax(0.0f),
componentId(0), componentId(0),
ui(new Ui::QGCComboBox) ui(new Ui::QGCToolWidgetComboBox)
{ {
ui->setupUi(this); ui->setupUi(this);
uas = NULL; uas = NULL;
...@@ -64,12 +64,12 @@ QGCComboBox::QGCComboBox(QWidget *parent) : ...@@ -64,12 +64,12 @@ QGCComboBox::QGCComboBox(QWidget *parent) :
init(); init();
} }
QGCComboBox::~QGCComboBox() QGCToolWidgetComboBox::~QGCToolWidgetComboBox()
{ {
delete ui; delete ui;
} }
void QGCComboBox::showTooltip() void QGCToolWidgetComboBox::showTooltip()
{ {
QWidget* sender = dynamic_cast<QWidget*>(QObject::sender()); QWidget* sender = dynamic_cast<QWidget*>(QObject::sender());
...@@ -80,7 +80,7 @@ void QGCComboBox::showTooltip() ...@@ -80,7 +80,7 @@ void QGCComboBox::showTooltip()
} }
} }
void QGCComboBox::refreshParameter() void QGCToolWidgetComboBox::refreshParameter()
{ {
ui->editSelectParamComboBox->setEnabled(true); ui->editSelectParamComboBox->setEnabled(true);
ui->editSelectComponentComboBox->setEnabled(true); ui->editSelectComponentComboBox->setEnabled(true);
...@@ -90,7 +90,7 @@ void QGCComboBox::refreshParameter() ...@@ -90,7 +90,7 @@ void QGCComboBox::refreshParameter()
} }
} }
void QGCComboBox::setActiveUAS(UASInterface* activeUas) void QGCToolWidgetComboBox::setActiveUAS(UASInterface* activeUas)
{ {
if (activeUas) if (activeUas)
{ {
...@@ -119,7 +119,7 @@ void QGCComboBox::setActiveUAS(UASInterface* activeUas) ...@@ -119,7 +119,7 @@ void QGCComboBox::setActiveUAS(UASInterface* activeUas)
} }
} }
void QGCComboBox::requestParameter() void QGCToolWidgetComboBox::requestParameter()
{ {
if (!parameterName.isEmpty() && uas) if (!parameterName.isEmpty() && uas)
{ {
...@@ -127,18 +127,18 @@ void QGCComboBox::requestParameter() ...@@ -127,18 +127,18 @@ void QGCComboBox::requestParameter()
} }
} }
void QGCComboBox::showInfo(bool enable) void QGCToolWidgetComboBox::showInfo(bool enable)
{ {
ui->editInfoCheckBox->setChecked(enable); ui->editInfoCheckBox->setChecked(enable);
ui->infoLabel->setVisible(enable); ui->infoLabel->setVisible(enable);
} }
void QGCComboBox::selectComponent(int componentIndex) void QGCToolWidgetComboBox::selectComponent(int componentIndex)
{ {
this->componentId = ui->editSelectComponentComboBox->itemData(componentIndex).toInt(); this->componentId = ui->editSelectComponentComboBox->itemData(componentIndex).toInt();
} }
void QGCComboBox::selectParameter(int paramIndex) void QGCToolWidgetComboBox::selectParameter(int paramIndex)
{ {
// Set name // Set name
parameterName = ui->editSelectParamComboBox->itemText(paramIndex); parameterName = ui->editSelectParamComboBox->itemText(paramIndex);
...@@ -165,7 +165,7 @@ void QGCComboBox::selectParameter(int paramIndex) ...@@ -165,7 +165,7 @@ void QGCComboBox::selectParameter(int paramIndex)
} }
} }
void QGCComboBox::setEditMode(bool editMode) void QGCToolWidgetComboBox::setEditMode(bool editMode)
{ {
if(!editMode) { if(!editMode) {
// Store component id // Store component id
...@@ -203,7 +203,7 @@ void QGCComboBox::setEditMode(bool editMode) ...@@ -203,7 +203,7 @@ void QGCComboBox::setEditMode(bool editMode)
QGCToolWidgetItem::setEditMode(editMode); QGCToolWidgetItem::setEditMode(editMode);
} }
void QGCComboBox::setParamPending() void QGCToolWidgetComboBox::setParamPending()
{ {
if (uas) { if (uas) {
uas->getParamManager()->setPendingParam(componentId, parameterName, parameterValue); uas->getParamManager()->setPendingParam(componentId, parameterName, parameterValue);
...@@ -220,7 +220,7 @@ void QGCComboBox::setParamPending() ...@@ -220,7 +220,7 @@ void QGCComboBox::setParamPending()
* @brief parameterName Key/name of the parameter * @brief parameterName Key/name of the parameter
* @brief value Value of the parameter * @brief value Value of the parameter
*/ */
void QGCComboBox::setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, QVariant value) void QGCToolWidgetComboBox::setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, QVariant value)
{ {
Q_UNUSED(paramCount); Q_UNUSED(paramCount);
// Check if this component and parameter are part of the list // Check if this component and parameter are part of the list
...@@ -301,7 +301,7 @@ void QGCComboBox::setParameterValue(int uas, int component, int paramCount, int ...@@ -301,7 +301,7 @@ void QGCComboBox::setParameterValue(int uas, int component, int paramCount, int
} }
} }
void QGCComboBox::changeEvent(QEvent *e) void QGCToolWidgetComboBox::changeEvent(QEvent *e)
{ {
QWidget::changeEvent(e); QWidget::changeEvent(e);
switch (e->type()) { switch (e->type()) {
...@@ -314,7 +314,7 @@ void QGCComboBox::changeEvent(QEvent *e) ...@@ -314,7 +314,7 @@ void QGCComboBox::changeEvent(QEvent *e)
} }
void QGCComboBox::writeSettings(QSettings& settings) void QGCToolWidgetComboBox::writeSettings(QSettings& settings)
{ {
settings.setValue("TYPE", "COMBOBOX"); settings.setValue("TYPE", "COMBOBOX");
settings.setValue("QGC_PARAM_COMBOBOX_DESCRIPTION", ui->nameLabel->text()); settings.setValue("QGC_PARAM_COMBOBOX_DESCRIPTION", ui->nameLabel->text());
...@@ -331,7 +331,7 @@ void QGCComboBox::writeSettings(QSettings& settings) ...@@ -331,7 +331,7 @@ void QGCComboBox::writeSettings(QSettings& settings)
} }
settings.sync(); settings.sync();
} }
void QGCComboBox::readSettings(const QString& pre,const QVariantMap& settings) void QGCToolWidgetComboBox::readSettings(const QString& pre,const QVariantMap& settings)
{ {
parameterName = settings.value(pre + "QGC_PARAM_COMBOBOX_PARAMID").toString(); parameterName = settings.value(pre + "QGC_PARAM_COMBOBOX_PARAMID").toString();
componentId = settings.value(pre + "QGC_PARAM_COMBOBOX_COMPONENTID").toInt(); componentId = settings.value(pre + "QGC_PARAM_COMBOBOX_COMPONENTID").toInt();
...@@ -370,7 +370,7 @@ void QGCComboBox::readSettings(const QString& pre,const QVariantMap& settings) ...@@ -370,7 +370,7 @@ void QGCComboBox::readSettings(const QString& pre,const QVariantMap& settings)
// Get param value after settings have been loaded // Get param value after settings have been loaded
// requestParameter(); // requestParameter();
} }
void QGCComboBox::readSettings(const QSettings& settings) void QGCToolWidgetComboBox::readSettings(const QSettings& settings)
{ {
QVariantMap map; QVariantMap map;
foreach (QString key,settings.allKeys()) foreach (QString key,settings.allKeys())
...@@ -410,19 +410,19 @@ void QGCComboBox::readSettings(const QSettings& settings) ...@@ -410,19 +410,19 @@ void QGCComboBox::readSettings(const QSettings& settings)
// Get param value after settings have been loaded // Get param value after settings have been loaded
//requestParameter(); //requestParameter();
} }
void QGCComboBox::addButtonClicked() void QGCToolWidgetComboBox::addButtonClicked()
{ {
ui->editOptionComboBox->addItem(ui->editItemNameLabel->text()); ui->editOptionComboBox->addItem(ui->editItemNameLabel->text());
comboBoxTextToValMap[ui->editItemNameLabel->text()] = ui->editItemValueSpinBox->value(); comboBoxTextToValMap[ui->editItemNameLabel->text()] = ui->editItemValueSpinBox->value();
} }
void QGCComboBox::delButtonClicked() void QGCToolWidgetComboBox::delButtonClicked()
{ {
int index = ui->editOptionComboBox->currentIndex(); int index = ui->editOptionComboBox->currentIndex();
comboBoxTextToValMap.remove(ui->editOptionComboBox->currentText()); comboBoxTextToValMap.remove(ui->editOptionComboBox->currentText());
ui->editOptionComboBox->removeItem(index); ui->editOptionComboBox->removeItem(index);
} }
void QGCComboBox::comboBoxIndexChanged(QString val) void QGCToolWidgetComboBox::comboBoxIndexChanged(QString val)
{ {
ui->imageLabel->setPixmap(comboBoxIndexToPixmap[ui->editOptionComboBox->currentIndex()]); ui->imageLabel->setPixmap(comboBoxIndexToPixmap[ui->editOptionComboBox->currentIndex()]);
if (comboBoxTextToParamMap.contains(ui->editOptionComboBox->currentText())) if (comboBoxTextToParamMap.contains(ui->editOptionComboBox->currentText()))
......
#ifndef QGCCOMBOBOX_H #ifndef QGCToolWidgetComboBox_H
#define QGCCOMBOBOX_H #define QGCToolWidgetComboBox_H
#include <QWidget> #include <QWidget>
#include <QAction> #include <QAction>
...@@ -11,16 +11,16 @@ class QGCUASParamManagerInterface; ...@@ -11,16 +11,16 @@ class QGCUASParamManagerInterface;
namespace Ui namespace Ui
{ {
class QGCComboBox; class QGCToolWidgetComboBox;
} }
class QGCComboBox : public QGCToolWidgetItem class QGCToolWidgetComboBox : public QGCToolWidgetItem
{ {
Q_OBJECT Q_OBJECT
public: public:
explicit QGCComboBox(QWidget *parent = 0); explicit QGCToolWidgetComboBox(QWidget *parent = 0);
~QGCComboBox(); ~QGCToolWidgetComboBox();
virtual void setEditMode(bool editMode); virtual void setEditMode(bool editMode);
...@@ -70,7 +70,7 @@ protected: ...@@ -70,7 +70,7 @@ protected:
void changeEvent(QEvent *e); void changeEvent(QEvent *e);
private: private:
Ui::QGCComboBox *ui; Ui::QGCToolWidgetComboBox *ui;
}; };
#endif // QGCCOMBOBOX_H #endif // QGCToolWidgetComboBox_H
<?xml version="1.0" encoding="UTF-8"?> <?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0"> <ui version="4.0">
<class>QGCComboBox</class> <class>QGCToolWidgetComboBox</class>
<widget class="QWidget" name="QGCComboBox"> <widget class="QWidget" name="QGCToolWidgetComboBox">
<property name="geometry"> <property name="geometry">
<rect> <rect>
<x>0</x> <x>0</x>
......
...@@ -86,7 +86,6 @@ PX4RCCalibration::PX4RCCalibration(QWidget *parent) : ...@@ -86,7 +86,6 @@ PX4RCCalibration::PX4RCCalibration(QWidget *parent) :
_rcCalState(rcCalStateChannelWait), _rcCalState(rcCalStateChannelWait),
_mav(NULL), _mav(NULL),
_paramMgr(NULL), _paramMgr(NULL),
_parameterListUpToDateSignalled(false),
_ui(new Ui::PX4RCCalibration), _ui(new Ui::PX4RCCalibration),
_unitTestMode(false) _unitTestMode(false)
{ {
...@@ -120,15 +119,21 @@ PX4RCCalibration::PX4RCCalibration(QWidget *parent) : ...@@ -120,15 +119,21 @@ PX4RCCalibration::PX4RCCalibration(QWidget *parent) :
_rgAttitudeControl[4].function = rcCalFunctionFlaps; _rgAttitudeControl[4].function = rcCalFunctionFlaps;
_rgAttitudeControl[4].valueWidget = _ui->flapsValue; _rgAttitudeControl[4].valueWidget = _ui->flapsValue;
_setActiveUAS(UASManager::instance()->getActiveUAS()); // This code assume we already have an active UAS with ready parameters
_mav = UASManager::instance()->getActiveUAS();
Q_ASSERT(_mav);
// Connect new signals
// Connect signals
bool fSucceeded; bool fSucceeded;
Q_UNUSED(fSucceeded); Q_UNUSED(fSucceeded);
fSucceeded = connect(_mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(_remoteControlChannelRawChanged(int,float)));
fSucceeded = connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(_setActiveUAS(UASInterface*)));
Q_ASSERT(fSucceeded); Q_ASSERT(fSucceeded);
_paramMgr = _mav->getParamManager();
Q_ASSERT(_paramMgr);
Q_ASSERT(_paramMgr->parametersReady());
connect(_ui->spektrumBind, &QPushButton::clicked, this, &PX4RCCalibration::_spektrumBind); connect(_ui->spektrumBind, &QPushButton::clicked, this, &PX4RCCalibration::_spektrumBind);
_updateTimer.setInterval(150); _updateTimer.setInterval(150);
...@@ -159,6 +164,9 @@ PX4RCCalibration::PX4RCCalibration(QWidget *parent) : ...@@ -159,6 +164,9 @@ PX4RCCalibration::PX4RCCalibration(QWidget *parent) :
connect(_ui->mode2, &QAbstractButton::toggled, this, &PX4RCCalibration::_mode2Toggled); connect(_ui->mode2, &QAbstractButton::toggled, this, &PX4RCCalibration::_mode2Toggled);
_stopCalibration(); _stopCalibration();
connect(&_updateTimer, &QTimer::timeout, this, &PX4RCCalibration::_updateView);
_setInternalCalibrationValuesFromParameters();
} }
PX4RCCalibration::~PX4RCCalibration() PX4RCCalibration::~PX4RCCalibration()
...@@ -699,84 +707,82 @@ void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void) ...@@ -699,84 +707,82 @@ void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void)
{ {
Q_ASSERT(_paramMgr); Q_ASSERT(_paramMgr);
if (_parameterListUpToDateSignalled) { // Initialize all function mappings to not set
// 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;
int componentId = _paramMgr->getDefaultComponentId();
for (int i = 0; i < _chanMax; ++i) {
struct ChannelInfo* info = &_rgChannelInfo[i];
for (size_t i=0; i<_chanMax; i++) { paramFound = _paramMgr->getParameterValue(componentId, trimTpl.arg(i+1), value);
struct ChannelInfo* info = &_rgChannelInfo[i]; Q_ASSERT(paramFound);
info->function = rcCalFunctionMax; if (paramFound) {
info->rcTrim = value.toInt(&convertOk);
Q_ASSERT(convertOk);
} }
for (size_t i=0; i<rcCalFunctionMax; i++) { paramFound = _paramMgr->getParameterValue(componentId, minTpl.arg(i+1), value);
_rgFunctionChannelMapping[i] = _chanMax; Q_ASSERT(paramFound);
if (paramFound) {
info->rcMin = value.toInt(&convertOk);
Q_ASSERT(convertOk);
} }
// 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;
int componentId = _paramMgr->getDefaultComponentId();
for (int i = 0; i < _chanMax; ++i) {
struct ChannelInfo* info = &_rgChannelInfo[i];
paramFound = _paramMgr->getParameterValue(componentId, trimTpl.arg(i+1), value);
Q_ASSERT(paramFound);
if (paramFound) {
info->rcTrim = value.toInt(&convertOk);
Q_ASSERT(convertOk);
}
paramFound = _paramMgr->getParameterValue(componentId, minTpl.arg(i+1), value);
Q_ASSERT(paramFound);
if (paramFound) {
info->rcMin = value.toInt(&convertOk);
Q_ASSERT(convertOk);
}
paramFound = _paramMgr->getParameterValue(componentId, maxTpl.arg(i+1), value); paramFound = _paramMgr->getParameterValue(componentId, maxTpl.arg(i+1), value);
Q_ASSERT(paramFound); Q_ASSERT(paramFound);
if (paramFound) { if (paramFound) {
info->rcMax = value.toInt(&convertOk); info->rcMax = value.toInt(&convertOk);
Q_ASSERT(convertOk); Q_ASSERT(convertOk);
} }
paramFound = _paramMgr->getParameterValue(componentId, revTpl.arg(i+1), value); paramFound = _paramMgr->getParameterValue(componentId, revTpl.arg(i+1), value);
Q_ASSERT(paramFound); Q_ASSERT(paramFound);
if (paramFound) { if (paramFound) {
float floatReversed = value.toFloat(&convertOk); float floatReversed = value.toFloat(&convertOk);
Q_ASSERT(convertOk); Q_ASSERT(convertOk);
Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f); Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f);
info->reversed = floatReversed == -1.0f; info->reversed = floatReversed == -1.0f;
}
} }
}
for (int i=0; i<rcCalFunctionMax; i++) {
int32_t paramChannel;
for (int i=0; i<rcCalFunctionMax; i++) { paramFound = _paramMgr->getParameterValue(componentId, _rgFunctionInfo[i].parameterName, value);
int32_t paramChannel; Q_ASSERT(paramFound);
if (paramFound) {
paramChannel = value.toInt(&convertOk);
Q_ASSERT(convertOk);
paramFound = _paramMgr->getParameterValue(componentId, _rgFunctionInfo[i].parameterName, value); if (paramChannel != 0) {
Q_ASSERT(paramFound); _rgFunctionChannelMapping[i] = paramChannel - 1;
if (paramFound) { _rgChannelInfo[paramChannel - 1].function = (enum rcCalFunctions)i;
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);
} }
_showMinMaxOnRadioWidgets(true);
_showTrimOnRadioWidgets(true);
} }
/// @brief Sets a connected Spektrum receiver into bind mode /// @brief Sets a connected Spektrum receiver into bind mode
...@@ -811,38 +817,6 @@ void PX4RCCalibration::_spektrumBind(void) ...@@ -811,38 +817,6 @@ void PX4RCCalibration::_spektrumBind(void)
} }
} }
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;
if (_mav) {
// Connect new signals
bool fSucceeded;
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);
if (_paramMgr->parametersReady()) {
_parameterListUpToDate();
}
}
setEnabled(_mav ? true : false);
}
/// @brief Validates the current settings against the calibration rules resetting values as necessary. /// @brief Validates the current settings against the calibration rules resetting values as necessary.
void PX4RCCalibration::_validateCalibration(void) void PX4RCCalibration::_validateCalibration(void)
{ {
...@@ -1073,17 +1047,6 @@ void PX4RCCalibration::_showTrimOnRadioWidgets(bool show) ...@@ -1073,17 +1047,6 @@ void PX4RCCalibration::_showTrimOnRadioWidgets(bool show)
} }
} }
void PX4RCCalibration::_parameterListUpToDate(void)
{
_parameterListUpToDateSignalled = true;
// Don't start updating the view until we have parameters
connect(&_updateTimer, &QTimer::timeout, this, &PX4RCCalibration::_updateView);
if (_currentStep == -1) {
_setInternalCalibrationValuesFromParameters();
}
}
void PX4RCCalibration::_loadSettings(void) void PX4RCCalibration::_loadSettings(void)
{ {
......
...@@ -71,9 +71,6 @@ private slots: ...@@ -71,9 +71,6 @@ private slots:
void _updateView(void); void _updateView(void);
void _remoteControlChannelRawChanged(int chan, float val); void _remoteControlChannelRawChanged(int chan, float val);
void _setActiveUAS(UASInterface* uas);
void _parameterListUpToDate(void);
private: private:
/// @brief These identify the various controls functions. They are also used as indices into the _rgFunctioInfo /// @brief These identify the various controls functions. They are also used as indices into the _rgFunctioInfo
...@@ -257,8 +254,6 @@ private: ...@@ -257,8 +254,6 @@ private:
UASInterface* _mav; ///< The current MAV UASInterface* _mav; ///< The current MAV
QGCUASParamManagerInterface* _paramMgr; QGCUASParamManagerInterface* _paramMgr;
bool _parameterListUpToDateSignalled; ///< true: we have received a parameterListUpToDate signal
Ui::PX4RCCalibration* _ui; Ui::PX4RCCalibration* _ui;
QTimer _updateTimer; ///< Timer used to update widgete ui QTimer _updateTimer; ///< Timer used to update widgete ui
......
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