LP-311 Remove basic/advanced stabilization tab auto-switch (autotune/txpid lock issues)
[librepilot.git] / ground / gcs / src / plugins / config / configrevonanohwwidget.cpp
blobb1d1ba6c7dfaef883a14a5b0f181303ccd41ff30
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 "configrevonanohwwidget.h"
30 #include "ui_configrevonanohwwidget.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 ConfigRevoNanoHWWidget::ConfigRevoNanoHWWidget(QWidget *parent) : ConfigTaskWidget(parent), m_refreshing(true)
44 m_ui = new Ui_RevoNanoHWWidget();
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 forceConnectedState();
58 addWidgetBinding("HwSettings", "RM_FlexiPort", m_ui->cbFlexi);
59 addWidgetBinding("HwSettings", "RM_MainPort", m_ui->cbMain);
60 addWidgetBinding("HwSettings", "RM_RcvrPort", m_ui->cbRcvr, 0, 1, true);
62 addWidgetBinding("HwSettings", "USB_HIDPort", m_ui->cbUSBHIDFunction);
63 addWidgetBinding("HwSettings", "USB_VCPPort", m_ui->cbUSBVCPFunction);
64 addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbUSBVCPSpeed);
66 addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbFlexiTelemSpeed);
67 addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbFlexiGPSSpeed);
68 addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbFlexiComSpeed);
70 addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbMainTelemSpeed);
71 addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
72 addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
74 addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbRcvrTelemSpeed);
75 addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbRcvrComSpeed);
77 // Add Gps protocol configuration
78 addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
79 addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol);
81 connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
82 setupCustomCombos();
83 enableControls(true);
84 populateWidgets();
85 refreshWidgetsValues();
86 setDirty(false);
87 m_refreshing = false;
90 ConfigRevoNanoHWWidget::~ConfigRevoNanoHWWidget()
92 // Do nothing
95 void ConfigRevoNanoHWWidget::setupCustomCombos()
97 connect(m_ui->cbUSBHIDFunction, SIGNAL(currentIndexChanged(int)), this, SLOT(usbHIDPortChanged(int)));
98 connect(m_ui->cbUSBVCPFunction, SIGNAL(currentIndexChanged(int)), this, SLOT(usbVCPPortChanged(int)));
100 connect(m_ui->cbFlexi, SIGNAL(currentIndexChanged(int)), this, SLOT(flexiPortChanged(int)));
101 connect(m_ui->cbMain, SIGNAL(currentIndexChanged(int)), this, SLOT(mainPortChanged(int)));
102 connect(m_ui->cbRcvr, SIGNAL(currentIndexChanged(int)), this, SLOT(rcvrPortChanged(int)));
105 void ConfigRevoNanoHWWidget::refreshWidgetsValues(UAVObject *obj)
107 m_refreshing = true;
108 ConfigTaskWidget::refreshWidgetsValues(obj);
110 usbVCPPortChanged(0);
111 mainPortChanged(0);
112 flexiPortChanged(0);
113 rcvrPortChanged(0);
114 m_refreshing = false;
117 void ConfigRevoNanoHWWidget::updateObjectsFromWidgets()
119 ConfigTaskWidget::updateObjectsFromWidgets();
121 HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
122 HwSettings::DataFields data = hwSettings->getData();
124 // If any port is configured to be GPS port, enable GPS module if it is not enabled.
125 // Otherwise disable GPS module.
126 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)
127 || isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
128 data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_ENABLED;
129 } else {
130 data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_DISABLED;
133 hwSettings->setData(data);
136 void ConfigRevoNanoHWWidget::usbVCPPortChanged(int index)
138 Q_UNUSED(index);
140 bool vcpComBridgeEnabled = isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_COMBRIDGE);
142 m_ui->lblUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
143 m_ui->cbUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
145 if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
146 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
148 enableComboBoxOptionItem(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE, vcpComBridgeEnabled);
150 if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) {
151 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
153 enableComboBoxOptionItem(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE, vcpComBridgeEnabled);
155 if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
156 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
158 enableComboBoxOptionItem(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE, vcpComBridgeEnabled);
160 // _DEBUGCONSOLE modes are mutual exclusive
161 if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
162 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
163 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
165 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
166 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
170 // _USBTELEMETRY modes are mutual exclusive
171 if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_USBTELEMETRY)
172 && isComboboxOptionSelected(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_USBTELEMETRY)) {
173 setComboboxSelectedOption(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_DISABLED);
177 void ConfigRevoNanoHWWidget::usbHIDPortChanged(int index)
179 Q_UNUSED(index);
181 // _USBTELEMETRY modes are mutual exclusive
182 if (isComboboxOptionSelected(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_USBTELEMETRY)
183 && isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_USBTELEMETRY)) {
184 setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
188 void ConfigRevoNanoHWWidget::flexiPortChanged(int index)
190 Q_UNUSED(index);
192 m_ui->cbFlexiTelemSpeed->setVisible(false);
193 m_ui->cbFlexiGPSSpeed->setVisible(false);
194 m_ui->cbFlexiComSpeed->setVisible(false);
195 m_ui->lblFlexiSpeed->setVisible(true);
197 // Add Gps protocol configuration
198 m_ui->cbFlexiGPSProtocol->setVisible(false);
199 m_ui->lbFlexiGPSProtocol->setVisible(false);
201 switch (getComboboxSelectedOption(m_ui->cbFlexi)) {
202 case HwSettings::RM_FLEXIPORT_TELEMETRY:
203 m_ui->cbFlexiTelemSpeed->setVisible(true);
204 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) {
205 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
207 if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)
208 || isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) {
209 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
211 break;
212 case HwSettings::RM_FLEXIPORT_GPS:
213 // Add Gps protocol configuration
214 m_ui->cbFlexiGPSProtocol->setVisible(true);
215 m_ui->lbFlexiGPSProtocol->setVisible(true);
217 m_ui->cbFlexiGPSSpeed->setVisible(true);
218 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
219 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
221 break;
222 case HwSettings::RM_FLEXIPORT_COMBRIDGE:
223 m_ui->cbFlexiComSpeed->setVisible(true);
224 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) {
225 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
227 if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
228 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
230 break;
231 case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE:
232 m_ui->cbFlexiComSpeed->setVisible(true);
233 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
234 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
236 if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
237 setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
239 break;
240 default:
241 m_ui->lblFlexiSpeed->setVisible(false);
242 break;
246 void ConfigRevoNanoHWWidget::mainPortChanged(int index)
248 Q_UNUSED(index);
250 m_ui->cbMainTelemSpeed->setVisible(false);
251 m_ui->cbMainGPSSpeed->setVisible(false);
252 m_ui->cbMainComSpeed->setVisible(false);
253 m_ui->lblMainSpeed->setVisible(true);
255 // Add Gps protocol configuration
256 m_ui->cbMainGPSProtocol->setVisible(false);
257 m_ui->lbMainGPSProtocol->setVisible(false);
259 switch (getComboboxSelectedOption(m_ui->cbMain)) {
260 case HwSettings::RM_MAINPORT_TELEMETRY:
261 m_ui->cbMainTelemSpeed->setVisible(true);
262 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
263 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
265 if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)
266 || isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) {
267 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
269 break;
270 case HwSettings::RM_MAINPORT_GPS:
271 // Add Gps protocol configuration
272 m_ui->cbMainGPSProtocol->setVisible(true);
273 m_ui->lbMainGPSProtocol->setVisible(true);
275 m_ui->cbMainGPSSpeed->setVisible(true);
276 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)) {
277 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
279 break;
280 case HwSettings::RM_MAINPORT_COMBRIDGE:
281 m_ui->cbMainComSpeed->setVisible(true);
282 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
283 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
285 if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
286 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
288 break;
289 case HwSettings::RM_MAINPORT_DEBUGCONSOLE:
290 m_ui->cbMainComSpeed->setVisible(true);
291 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
292 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
294 if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
295 setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
297 break;
298 default:
299 m_ui->lblMainSpeed->setVisible(false);
300 break;
304 void ConfigRevoNanoHWWidget::rcvrPortChanged(int index)
306 Q_UNUSED(index);
308 m_ui->lblRcvrSpeed->setVisible(true);
309 m_ui->cbRcvrTelemSpeed->setVisible(false);
310 m_ui->cbRcvrComSpeed->setVisible(false);
312 switch (getComboboxSelectedOption(m_ui->cbRcvr)) {
313 case HwSettings::RM_RCVRPORT_TELEMETRY:
314 case HwSettings::RM_RCVRPORT_PPMTELEMETRY:
315 m_ui->cbRcvrTelemSpeed->setVisible(true);
317 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
318 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
320 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) {
321 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
323 break;
324 case HwSettings::RM_RCVRPORT_COMBRIDGE:
325 m_ui->cbRcvrComSpeed->setVisible(true);
326 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
327 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
329 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) {
330 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
332 break;
333 default:
334 m_ui->lblRcvrSpeed->setVisible(false);
335 break;
339 void ConfigRevoNanoHWWidget::openHelp()
341 QDesktopServices::openUrl(QUrl(QString(WIKI_URL_ROOT) + QString("Revo+Nano+Configuration"),
342 QUrl::StrictMode));