LP-311 Remove basic/advanced stabilization tab auto-switch (autotune/txpid lock issues)
[librepilot.git] / ground / gcs / src / plugins / config / configrevohwwidget.cpp
blob7519c7300c1ffa4f1470d27e8a48a107e5b715b3
1 /**
2 ******************************************************************************
4 * @file configrevohwwidget.cpp
5 * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
6 * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
7 * @addtogroup GCSPlugins GCS Plugins
8 * @{
9 * @addtogroup ConfigPlugin Config Plugin
10 * @{
11 * @brief Revolution hardware configuration panel
12 *****************************************************************************/
14 * This program is free software; you can redistribute it and/or modify
15 * it under the terms of the GNU General Public License as published by
16 * the Free Software Foundation; either version 3 of the License, or
17 * (at your option) any later version.
19 * This program is distributed in the hope that it will be useful, but
20 * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
21 * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
22 * for more details.
24 * You should have received a copy of the GNU General Public License along
25 * with this program; if not, write to the Free Software Foundation, Inc.,
26 * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
28 #include "configrevohwwidget.h"
30 #include "ui_configrevohwwidget.h"
32 #include <extensionsystem/pluginmanager.h>
33 #include <coreplugin/generalsettings.h>
35 #include "hwsettings.h"
37 #include <QDebug>
38 #include <QDesktopServices>
39 #include <QUrl>
40 #include <QMessageBox>
42 ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(parent), m_refreshing(true)
44 m_ui = new Ui_RevoHWWidget();
45 m_ui->setupUi(this);
47 ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
48 Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
49 if (!settings->useExpertMode()) {
50 m_ui->saveTelemetryToRAM->setEnabled(false);
51 m_ui->saveTelemetryToRAM->setVisible(false);
54 addApplySaveButtons(m_ui->saveTelemetryToRAM, m_ui->saveTelemetryToSD);
56 addWidgetBinding("HwSettings", "RM_FlexiPort", m_ui->cbFlexi);
57 addWidgetBinding("HwSettings", "RM_MainPort", m_ui->cbMain);
58 addWidgetBinding("HwSettings", "RM_RcvrPort", m_ui->cbRcvr);
60 addWidgetBinding("HwSettings", "USB_HIDPort", m_ui->cbUSBHIDFunction);
61 addWidgetBinding("HwSettings", "USB_VCPPort", m_ui->cbUSBVCPFunction);
62 addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbUSBVCPSpeed);
64 addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbFlexiTelemSpeed);
65 addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbFlexiGPSSpeed);
66 addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbFlexiComSpeed);
68 addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbMainTelemSpeed);
69 addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
70 addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
72 addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbRcvrTelemSpeed);
73 addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbRcvrComSpeed);
75 // Add Gps protocol configuration
76 addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
77 addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol);
79 connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
81 setupCustomCombos();
82 enableControls(true);
83 populateWidgets();
84 refreshWidgetsValues();
85 forceConnectedState();
86 m_refreshing = false;
89 ConfigRevoHWWidget::~ConfigRevoHWWidget()
91 // Do nothing
94 void ConfigRevoHWWidget::setupCustomCombos()
96 connect(m_ui->cbUSBHIDFunction, SIGNAL(currentIndexChanged(int)), this, SLOT(usbHIDPortChanged(int)));
97 connect(m_ui->cbUSBVCPFunction, SIGNAL(currentIndexChanged(int)), this, SLOT(usbVCPPortChanged(int)));
99 m_ui->cbSonar->addItem(tr("Disabled"));
100 m_ui->cbSonar->setCurrentIndex(0);
101 m_ui->cbSonar->setEnabled(false);
103 connect(m_ui->cbFlexi, SIGNAL(currentIndexChanged(int)), this, SLOT(flexiPortChanged(int)));
104 connect(m_ui->cbMain, SIGNAL(currentIndexChanged(int)), this, SLOT(mainPortChanged(int)));
105 connect(m_ui->cbRcvr, SIGNAL(currentIndexChanged(int)), this, SLOT(rcvrPortChanged(int)));
108 void ConfigRevoHWWidget::refreshWidgetsValues(UAVObject *obj)
110 m_refreshing = true;
111 ConfigTaskWidget::refreshWidgetsValues(obj);
113 usbVCPPortChanged(0);
114 mainPortChanged(0);
115 flexiPortChanged(0);
116 rcvrPortChanged(0);
117 m_refreshing = false;
120 void ConfigRevoHWWidget::updateObjectsFromWidgets()
122 ConfigTaskWidget::updateObjectsFromWidgets();
124 HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
125 HwSettings::DataFields data = hwSettings->getData();
127 // If any port is configured to be GPS port, enable GPS module if it is not enabled.
128 // Otherwise disable GPS module.
129 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)
130 || isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
131 data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_ENABLED;
132 } else {
133 data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_DISABLED;
136 hwSettings->setData(data);
139 void ConfigRevoHWWidget::usbVCPPortChanged(int index)
141 Q_UNUSED(index);
143 bool vcpComBridgeEnabled = isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_COMBRIDGE);
145 m_ui->lblUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
146 m_ui->cbUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
148 if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
149 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
151 enableComboBoxOptionItem(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE, vcpComBridgeEnabled);
153 if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) {
154 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
156 enableComboBoxOptionItem(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE, vcpComBridgeEnabled);
158 if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
159 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
161 enableComboBoxOptionItem(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE, vcpComBridgeEnabled);
163 // _DEBUGCONSOLE modes are mutual exclusive
164 if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
165 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
166 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
168 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
169 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
173 // _USBTELEMETRY modes are mutual exclusive
174 if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_USBTELEMETRY)
175 && isComboboxOptionSelected(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_USBTELEMETRY)) {
176 setComboboxSelectedOption(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_DISABLED);
180 void ConfigRevoHWWidget::usbHIDPortChanged(int index)
182 Q_UNUSED(index);
184 // _USBTELEMETRY modes are mutual exclusive
185 if (isComboboxOptionSelected(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_USBTELEMETRY)
186 && isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_USBTELEMETRY)) {
187 setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
191 void ConfigRevoHWWidget::flexiPortChanged(int index)
193 Q_UNUSED(index);
195 m_ui->cbFlexiTelemSpeed->setVisible(false);
196 m_ui->cbFlexiGPSSpeed->setVisible(false);
197 m_ui->cbFlexiComSpeed->setVisible(false);
198 m_ui->lblFlexiSpeed->setVisible(true);
200 // Add Gps protocol configuration
201 m_ui->cbFlexiGPSProtocol->setVisible(false);
202 m_ui->lbFlexiGPSProtocol->setVisible(false);
204 switch (getComboboxSelectedOption(m_ui->cbFlexi)) {
205 case HwSettings::RM_FLEXIPORT_TELEMETRY:
206 m_ui->cbFlexiTelemSpeed->setVisible(true);
207 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) {
208 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
210 if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)
211 || isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) {
212 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
214 break;
215 case HwSettings::RM_FLEXIPORT_GPS:
216 // Add Gps protocol configuration
217 m_ui->cbFlexiGPSProtocol->setVisible(true);
218 m_ui->lbFlexiGPSProtocol->setVisible(true);
220 m_ui->cbFlexiGPSSpeed->setVisible(true);
221 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
222 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
224 break;
225 case HwSettings::RM_FLEXIPORT_COMBRIDGE:
226 m_ui->cbFlexiComSpeed->setVisible(true);
227 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) {
228 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
230 if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
231 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
233 break;
234 case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE:
235 m_ui->cbFlexiComSpeed->setVisible(true);
236 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
237 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
239 if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
240 setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
242 break;
243 default:
244 m_ui->lblFlexiSpeed->setVisible(false);
245 break;
249 void ConfigRevoHWWidget::mainPortChanged(int index)
251 Q_UNUSED(index);
253 m_ui->cbMainTelemSpeed->setVisible(false);
254 m_ui->cbMainGPSSpeed->setVisible(false);
255 m_ui->cbMainComSpeed->setVisible(false);
256 m_ui->lblMainSpeed->setVisible(true);
258 // Add Gps protocol configuration
259 m_ui->cbMainGPSProtocol->setVisible(false);
260 m_ui->lbMainGPSProtocol->setVisible(false);
262 switch (getComboboxSelectedOption(m_ui->cbMain)) {
263 case HwSettings::RM_MAINPORT_TELEMETRY:
264 m_ui->cbMainTelemSpeed->setVisible(true);
265 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
266 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
268 if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)
269 || isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) {
270 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
272 break;
273 case HwSettings::RM_MAINPORT_GPS:
274 // Add Gps protocol configuration
275 m_ui->cbMainGPSProtocol->setVisible(true);
276 m_ui->lbMainGPSProtocol->setVisible(true);
278 m_ui->cbMainGPSSpeed->setVisible(true);
279 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)) {
280 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
282 break;
283 case HwSettings::RM_MAINPORT_COMBRIDGE:
284 m_ui->cbMainComSpeed->setVisible(true);
285 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
286 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
288 if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
289 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
291 break;
292 case HwSettings::RM_MAINPORT_DEBUGCONSOLE:
293 m_ui->cbMainComSpeed->setVisible(true);
294 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
295 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
297 if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
298 setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
300 break;
301 default:
302 m_ui->lblMainSpeed->setVisible(false);
303 break;
307 void ConfigRevoHWWidget::rcvrPortChanged(int index)
309 Q_UNUSED(index);
310 m_ui->lblRcvrSpeed->setVisible(true);
311 m_ui->cbRcvrTelemSpeed->setVisible(false);
312 m_ui->cbRcvrComSpeed->setVisible(false);
314 switch (getComboboxSelectedOption(m_ui->cbRcvr)) {
315 case HwSettings::RM_RCVRPORT_TELEMETRY:
316 case HwSettings::RM_RCVRPORT_PPMTELEMETRY:
317 m_ui->cbRcvrTelemSpeed->setVisible(true);
319 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
320 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
322 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) {
323 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
325 break;
326 case HwSettings::RM_RCVRPORT_COMBRIDGE:
327 m_ui->cbRcvrComSpeed->setVisible(true);
328 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
329 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
331 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) {
332 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
334 break;
335 default:
336 m_ui->lblRcvrSpeed->setVisible(false);
337 break;
341 void ConfigRevoHWWidget::openHelp()
343 QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("Revolution+Configuration"),
344 QUrl::StrictMode));