LP-56 - Better txpid option namings, fix tabs-spaces, tooltips. headers, variable...
[librepilot.git] / ground / openpilotgcs / src / plugins / config / configrevonanohwwidget.cpp
blob3c56dd338c9cbb9fcdbd403f8ebfb167b1a28860
1 /**
2 ******************************************************************************
4 * @file configrevohwwidget.cpp
5 * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
6 * @addtogroup GCSPlugins GCS Plugins
7 * @{
8 * @addtogroup ConfigPlugin Config Plugin
9 * @{
10 * @brief Revolution hardware configuration panel
11 *****************************************************************************/
13 * This program is free software; you can redistribute it and/or modify
14 * it under the terms of the GNU General Public License as published by
15 * the Free Software Foundation; either version 3 of the License, or
16 * (at your option) any later version.
18 * This program is distributed in the hope that it will be useful, but
19 * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
20 * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
21 * for more details.
23 * You should have received a copy of the GNU General Public License along
24 * with this program; if not, write to the Free Software Foundation, Inc.,
25 * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
27 #include "configrevonanohwwidget.h"
29 #include <QDebug>
30 #include <extensionsystem/pluginmanager.h>
31 #include <coreplugin/generalsettings.h>
32 #include "hwsettings.h"
33 #include <QDesktopServices>
34 #include <QUrl>
35 #include <QMessageBox>
38 ConfigRevoNanoHWWidget::ConfigRevoNanoHWWidget(QWidget *parent) : ConfigTaskWidget(parent), m_refreshing(true)
40 m_ui = new Ui_RevoNanoHWWidget();
41 m_ui->setupUi(this);
43 ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
44 Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
45 if (!settings->useExpertMode()) {
46 m_ui->saveTelemetryToRAM->setEnabled(false);
47 m_ui->saveTelemetryToRAM->setVisible(false);
50 addApplySaveButtons(m_ui->saveTelemetryToRAM, m_ui->saveTelemetryToSD);
52 forceConnectedState();
54 addWidgetBinding("HwSettings", "RM_FlexiPort", m_ui->cbFlexi);
55 addWidgetBinding("HwSettings", "RM_MainPort", m_ui->cbMain);
56 addWidgetBinding("HwSettings", "RM_RcvrPort", m_ui->cbRcvr, 0, 1, true);
58 addWidgetBinding("HwSettings", "USB_HIDPort", m_ui->cbUSBHIDFunction);
59 addWidgetBinding("HwSettings", "USB_VCPPort", m_ui->cbUSBVCPFunction);
60 addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbUSBVCPSpeed);
62 addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbFlexiTelemSpeed);
63 addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbFlexiGPSSpeed);
64 addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbFlexiComSpeed);
66 addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbMainTelemSpeed);
67 addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
68 addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
70 addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbRcvrTelemSpeed);
71 addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbRcvrComSpeed);
73 // Add Gps protocol configuration
74 addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
75 addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol);
77 connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
78 setupCustomCombos();
79 enableControls(true);
80 populateWidgets();
81 refreshWidgetsValues();
82 setDirty(false);
83 m_refreshing = false;
86 ConfigRevoNanoHWWidget::~ConfigRevoNanoHWWidget()
88 // Do nothing
91 void ConfigRevoNanoHWWidget::setupCustomCombos()
93 connect(m_ui->cbUSBHIDFunction, SIGNAL(currentIndexChanged(int)), this, SLOT(usbHIDPortChanged(int)));
94 connect(m_ui->cbUSBVCPFunction, SIGNAL(currentIndexChanged(int)), this, SLOT(usbVCPPortChanged(int)));
96 connect(m_ui->cbFlexi, SIGNAL(currentIndexChanged(int)), this, SLOT(flexiPortChanged(int)));
97 connect(m_ui->cbMain, SIGNAL(currentIndexChanged(int)), this, SLOT(mainPortChanged(int)));
98 connect(m_ui->cbRcvr, SIGNAL(currentIndexChanged(int)), this, SLOT(rcvrPortChanged(int)));
101 void ConfigRevoNanoHWWidget::refreshWidgetsValues(UAVObject *obj)
103 m_refreshing = true;
104 ConfigTaskWidget::refreshWidgetsValues(obj);
106 usbVCPPortChanged(0);
107 mainPortChanged(0);
108 flexiPortChanged(0);
109 rcvrPortChanged(0);
110 m_refreshing = false;
113 void ConfigRevoNanoHWWidget::updateObjectsFromWidgets()
115 ConfigTaskWidget::updateObjectsFromWidgets();
117 HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
118 HwSettings::DataFields data = hwSettings->getData();
120 // If any port is configured to be GPS port, enable GPS module if it is not enabled.
121 // Otherwise disable GPS module.
122 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)
123 || isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
124 data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_ENABLED;
125 } else {
126 data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_DISABLED;
129 hwSettings->setData(data);
132 void ConfigRevoNanoHWWidget::usbVCPPortChanged(int index)
134 Q_UNUSED(index);
136 bool vcpComBridgeEnabled = isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_COMBRIDGE);
138 m_ui->lblUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
139 m_ui->cbUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
141 if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
142 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
144 enableComboBoxOptionItem(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE, vcpComBridgeEnabled);
146 if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) {
147 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
149 enableComboBoxOptionItem(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE, vcpComBridgeEnabled);
151 if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
152 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
154 enableComboBoxOptionItem(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE, vcpComBridgeEnabled);
156 // _DEBUGCONSOLE modes are mutual exclusive
157 if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
158 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
159 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
161 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
162 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
166 // _USBTELEMETRY modes are mutual exclusive
167 if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_USBTELEMETRY)
168 && isComboboxOptionSelected(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_USBTELEMETRY)) {
169 setComboboxSelectedOption(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_DISABLED);
173 void ConfigRevoNanoHWWidget::usbHIDPortChanged(int index)
175 Q_UNUSED(index);
177 // _USBTELEMETRY modes are mutual exclusive
178 if (isComboboxOptionSelected(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_USBTELEMETRY)
179 && isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_USBTELEMETRY)) {
180 setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
184 void ConfigRevoNanoHWWidget::flexiPortChanged(int index)
186 Q_UNUSED(index);
188 m_ui->cbFlexiTelemSpeed->setVisible(false);
189 m_ui->cbFlexiGPSSpeed->setVisible(false);
190 m_ui->cbFlexiComSpeed->setVisible(false);
191 m_ui->lblFlexiSpeed->setVisible(true);
193 // Add Gps protocol configuration
194 m_ui->cbFlexiGPSProtocol->setVisible(false);
195 m_ui->lbFlexiGPSProtocol->setVisible(false);
197 switch (getComboboxSelectedOption(m_ui->cbFlexi)) {
198 case HwSettings::RM_FLEXIPORT_TELEMETRY:
199 m_ui->cbFlexiTelemSpeed->setVisible(true);
200 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) {
201 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
203 if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)
204 || isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) {
205 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
207 break;
208 case HwSettings::RM_FLEXIPORT_GPS:
209 // Add Gps protocol configuration
210 m_ui->cbFlexiGPSProtocol->setVisible(true);
211 m_ui->lbFlexiGPSProtocol->setVisible(true);
213 m_ui->cbFlexiGPSSpeed->setVisible(true);
214 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
215 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
217 break;
218 case HwSettings::RM_FLEXIPORT_COMBRIDGE:
219 m_ui->cbFlexiComSpeed->setVisible(true);
220 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) {
221 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
223 if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
224 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
226 break;
227 case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE:
228 m_ui->cbFlexiComSpeed->setVisible(true);
229 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
230 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
232 if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
233 setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
235 break;
236 default:
237 m_ui->lblFlexiSpeed->setVisible(false);
238 break;
242 void ConfigRevoNanoHWWidget::mainPortChanged(int index)
244 Q_UNUSED(index);
246 m_ui->cbMainTelemSpeed->setVisible(false);
247 m_ui->cbMainGPSSpeed->setVisible(false);
248 m_ui->cbMainComSpeed->setVisible(false);
249 m_ui->lblMainSpeed->setVisible(true);
251 // Add Gps protocol configuration
252 m_ui->cbMainGPSProtocol->setVisible(false);
253 m_ui->lbMainGPSProtocol->setVisible(false);
255 switch (getComboboxSelectedOption(m_ui->cbMain)) {
256 case HwSettings::RM_MAINPORT_TELEMETRY:
257 m_ui->cbMainTelemSpeed->setVisible(true);
258 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
259 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
261 if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)
262 || isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) {
263 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
265 break;
266 case HwSettings::RM_MAINPORT_GPS:
267 // Add Gps protocol configuration
268 m_ui->cbMainGPSProtocol->setVisible(true);
269 m_ui->lbMainGPSProtocol->setVisible(true);
271 m_ui->cbMainGPSSpeed->setVisible(true);
272 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)) {
273 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
275 break;
276 case HwSettings::RM_MAINPORT_COMBRIDGE:
277 m_ui->cbMainComSpeed->setVisible(true);
278 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
279 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
281 if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
282 setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
284 break;
285 case HwSettings::RM_MAINPORT_DEBUGCONSOLE:
286 m_ui->cbMainComSpeed->setVisible(true);
287 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
288 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
290 if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
291 setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
293 break;
294 default:
295 m_ui->lblMainSpeed->setVisible(false);
296 break;
300 void ConfigRevoNanoHWWidget::rcvrPortChanged(int index)
302 Q_UNUSED(index);
304 m_ui->lblRcvrSpeed->setVisible(true);
305 m_ui->cbRcvrTelemSpeed->setVisible(false);
306 m_ui->cbRcvrComSpeed->setVisible(false);
308 switch (getComboboxSelectedOption(m_ui->cbRcvr)) {
309 case HwSettings::RM_RCVRPORT_TELEMETRY:
310 case HwSettings::RM_RCVRPORT_PPMTELEMETRY:
311 m_ui->cbRcvrTelemSpeed->setVisible(true);
313 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
314 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
316 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
317 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_FLEXIPORT_DISABLED);
319 break;
320 case HwSettings::RM_RCVRPORT_COMBRIDGE:
321 m_ui->cbRcvrComSpeed->setVisible(true);
322 if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
323 setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
325 if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) {
326 setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
328 break;
329 default:
330 m_ui->lblRcvrSpeed->setVisible(false);
331 break;
335 void ConfigRevoNanoHWWidget::openHelp()
337 QDesktopServices::openUrl(QUrl(tr("http://wiki.openpilot.org/x/GgDBAQ"), QUrl::StrictMode));