2 ******************************************************************************
4 * @file configrevohwwidget.cpp
5 * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
6 * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
7 * @addtogroup GCSPlugins GCS Plugins
9 * @addtogroup ConfigPlugin Config Plugin
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
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 "hwsettings.h"
36 ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget
*parent
) : ConfigTaskWidget(parent
)
38 m_ui
= new Ui_RevoHWWidget();
41 m_ui
->boardImg
->load(QString(":/configgadget/images/revolution.svg"));
42 QSize picSize
= m_ui
->boardImg
->sizeHint();
43 picSize
.scale(360, 360, Qt::KeepAspectRatio
);
44 m_ui
->boardImg
->setFixedSize(picSize
);
46 // must be done before auto binding !
47 setWikiURL("Revolution+Configuration");
51 addUAVObject("HwSettings");
53 addWidgetBinding("HwSettings", "RM_FlexiPort", m_ui
->cbFlexi
);
54 addWidgetBinding("HwSettings", "RM_MainPort", m_ui
->cbMain
);
55 addWidgetBinding("HwSettings", "RM_RcvrPort", m_ui
->cbRcvr
);
57 addWidgetBinding("HwSettings", "USB_HIDPort", m_ui
->cbUSBHIDFunction
);
58 addWidgetBinding("HwSettings", "USB_VCPPort", m_ui
->cbUSBVCPFunction
);
60 addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui
->cbFlexiTelemSpeed
);
61 addWidgetBinding("HwSettings", "GPSSpeed", m_ui
->cbFlexiGPSSpeed
);
63 addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui
->cbMainTelemSpeed
);
64 addWidgetBinding("HwSettings", "GPSSpeed", m_ui
->cbMainGPSSpeed
);
66 addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui
->cbRcvrTelemSpeed
);
67 addWidgetBinding("HwSettings", "GPSSpeed", m_ui
->cbRcvrGPSSpeed
);
69 // Add Gps protocol configuration
70 addWidgetBinding("GPSSettings", "DataProtocol", m_ui
->cbMainGPSProtocol
);
71 addWidgetBinding("GPSSettings", "DataProtocol", m_ui
->cbFlexiGPSProtocol
);
72 addWidgetBinding("GPSSettings", "DataProtocol", m_ui
->cbRcvrGPSProtocol
);
74 addWidgetBinding("HwSettings", "RadioAuxStream", m_ui
->cbRadioAux
);
79 ConfigRevoHWWidget::~ConfigRevoHWWidget()
84 void ConfigRevoHWWidget::setupCustomCombos()
86 connect(m_ui
->cbUSBHIDFunction
, SIGNAL(currentIndexChanged(int)), this, SLOT(usbHIDPortChanged(int)));
87 connect(m_ui
->cbUSBVCPFunction
, SIGNAL(currentIndexChanged(int)), this, SLOT(usbVCPPortChanged(int)));
89 m_ui
->cbSonar
->addItem(tr("Disabled"));
90 m_ui
->cbSonar
->setCurrentIndex(0);
91 m_ui
->cbSonar
->setEnabled(false);
93 connect(m_ui
->cbFlexi
, SIGNAL(currentIndexChanged(int)), this, SLOT(flexiPortChanged(int)));
94 connect(m_ui
->cbMain
, SIGNAL(currentIndexChanged(int)), this, SLOT(mainPortChanged(int)));
95 connect(m_ui
->cbRcvr
, SIGNAL(currentIndexChanged(int)), this, SLOT(rcvrPortChanged(int)));
98 void ConfigRevoHWWidget::refreshWidgetsValuesImpl(UAVObject
*obj
)
102 usbVCPPortChanged(0);
108 void ConfigRevoHWWidget::updateObjectsFromWidgetsImpl()
110 // If any port is configured to be GPS port, enable GPS module if it is not enabled.
111 // GPS module will be already built in for Revo board, keep this check just in case.
112 HwSettings
*hwSettings
= HwSettings::GetInstance(getObjectManager());
114 if ((hwSettings
->optionalModulesGPS() == HwSettings_OptionalModules::Disabled
) &&
115 (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_GPS
) ||
116 isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_GPS
))) {
117 hwSettings
->setOptionalModulesGPS(HwSettings_OptionalModules::Enabled
);
121 void ConfigRevoHWWidget::usbVCPPortChanged(int index
)
125 bool vcpComBridgeEnabled
= isComboboxOptionSelected(m_ui
->cbUSBVCPFunction
, HwSettings::USB_VCPPORT_COMBRIDGE
);
127 if (!vcpComBridgeEnabled
&& isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_COMBRIDGE
)) {
128 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
130 enableComboBoxOptionItem(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_COMBRIDGE
, vcpComBridgeEnabled
);
132 if (!vcpComBridgeEnabled
&& isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_COMBRIDGE
)) {
133 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
135 enableComboBoxOptionItem(m_ui
->cbMain
, HwSettings::RM_MAINPORT_COMBRIDGE
, vcpComBridgeEnabled
);
137 if (!vcpComBridgeEnabled
&& isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_COMBRIDGE
)) {
138 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
140 if (!vcpComBridgeEnabled
&& isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE
)) {
141 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
144 enableComboBoxOptionItem(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_COMBRIDGE
, vcpComBridgeEnabled
);
145 enableComboBoxOptionItem(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE
, vcpComBridgeEnabled
);
147 // _DEBUGCONSOLE modes are mutual exclusive
148 if (isComboboxOptionSelected(m_ui
->cbUSBVCPFunction
, HwSettings::USB_VCPPORT_DEBUGCONSOLE
)) {
149 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DEBUGCONSOLE
)) {
150 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
152 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE
)) {
153 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
155 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DEBUGCONSOLE
)) {
156 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
158 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE
)) {
159 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
163 // _USBTELEMETRY modes are mutual exclusive
164 if (isComboboxOptionSelected(m_ui
->cbUSBVCPFunction
, HwSettings::USB_VCPPORT_USBTELEMETRY
)
165 && isComboboxOptionSelected(m_ui
->cbUSBHIDFunction
, HwSettings::USB_HIDPORT_USBTELEMETRY
)) {
166 setComboboxSelectedOption(m_ui
->cbUSBHIDFunction
, HwSettings::USB_HIDPORT_DISABLED
);
170 void ConfigRevoHWWidget::usbHIDPortChanged(int index
)
174 // _USBTELEMETRY modes are mutual exclusive
175 if (isComboboxOptionSelected(m_ui
->cbUSBHIDFunction
, HwSettings::USB_HIDPORT_USBTELEMETRY
)
176 && isComboboxOptionSelected(m_ui
->cbUSBVCPFunction
, HwSettings::USB_VCPPORT_USBTELEMETRY
)) {
177 setComboboxSelectedOption(m_ui
->cbUSBVCPFunction
, HwSettings::USB_VCPPORT_DISABLED
);
181 void ConfigRevoHWWidget::flexiPortChanged(int index
)
185 m_ui
->cbFlexiTelemSpeed
->setVisible(false);
186 m_ui
->cbFlexiGPSSpeed
->setVisible(false);
187 m_ui
->lblFlexiSpeed
->setVisible(true);
189 // Add Gps protocol configuration
190 m_ui
->cbFlexiGPSProtocol
->setVisible(false);
191 m_ui
->lbFlexiGPSProtocol
->setVisible(false);
193 switch (getComboboxSelectedOption(m_ui
->cbFlexi
)) {
194 case HwSettings::RM_FLEXIPORT_TELEMETRY
:
195 m_ui
->cbFlexiTelemSpeed
->setVisible(true);
196 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_TELEMETRY
)) {
197 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
199 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMTELEMETRY
)) {
200 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
202 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_TELEMETRY
)) {
203 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
206 case HwSettings::RM_FLEXIPORT_GPS
:
207 // Add Gps protocol configuration
208 m_ui
->cbFlexiGPSProtocol
->setVisible(true);
209 m_ui
->lbFlexiGPSProtocol
->setVisible(true);
211 m_ui
->cbFlexiGPSSpeed
->setVisible(true);
212 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_GPS
)) {
213 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
215 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMGPS
)) {
216 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
218 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_GPS
)) {
219 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
223 case HwSettings::RM_FLEXIPORT_COMBRIDGE
:
224 m_ui
->lblFlexiSpeed
->setVisible(false);
225 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_COMBRIDGE
)) {
226 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
228 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_COMBRIDGE
)) {
229 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
231 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE
)) {
232 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
235 case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE
:
236 m_ui
->lblFlexiSpeed
->setVisible(false);
237 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DEBUGCONSOLE
)) {
238 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
240 if (isComboboxOptionSelected(m_ui
->cbUSBVCPFunction
, HwSettings::USB_VCPPORT_DEBUGCONSOLE
)) {
241 setComboboxSelectedOption(m_ui
->cbUSBVCPFunction
, HwSettings::USB_VCPPORT_DISABLED
);
243 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE
)) {
244 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
246 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DEBUGCONSOLE
)) {
247 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
250 case HwSettings::RM_FLEXIPORT_OSDHK
:
251 m_ui
->lblFlexiSpeed
->setVisible(false);
252 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_OSDHK
)) {
253 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
256 case HwSettings::RM_FLEXIPORT_MSP
:
257 m_ui
->lblFlexiSpeed
->setVisible(false);
258 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_MSP
)) {
259 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
261 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_MSP
)) {
262 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
264 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMMSP
)) {
265 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
268 case HwSettings::RM_FLEXIPORT_MAVLINK
:
269 m_ui
->lblFlexiSpeed
->setVisible(false);
270 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_MAVLINK
)) {
271 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
273 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_MAVLINK
)) {
274 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
276 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMMAVLINK
)) {
277 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
281 m_ui
->lblFlexiSpeed
->setVisible(false);
286 void ConfigRevoHWWidget::mainPortChanged(int index
)
290 m_ui
->cbMainTelemSpeed
->setVisible(false);
291 m_ui
->cbMainGPSSpeed
->setVisible(false);
292 m_ui
->lblMainSpeed
->setVisible(true);
294 // Add Gps protocol configuration
295 m_ui
->cbMainGPSProtocol
->setVisible(false);
296 m_ui
->lbMainGPSProtocol
->setVisible(false);
298 switch (getComboboxSelectedOption(m_ui
->cbMain
)) {
299 case HwSettings::RM_MAINPORT_TELEMETRY
:
300 m_ui
->cbMainTelemSpeed
->setVisible(true);
301 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_TELEMETRY
)) {
302 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
304 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMTELEMETRY
)) {
305 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
307 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_TELEMETRY
)) {
308 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
311 case HwSettings::RM_MAINPORT_GPS
:
312 // Add Gps protocol configuration
313 m_ui
->cbMainGPSProtocol
->setVisible(true);
314 m_ui
->lbMainGPSProtocol
->setVisible(true);
316 m_ui
->cbMainGPSSpeed
->setVisible(true);
317 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_GPS
)) {
318 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
320 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMGPS
)) {
321 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
323 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_GPS
)) {
324 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
327 case HwSettings::RM_MAINPORT_COMBRIDGE
:
328 m_ui
->lblMainSpeed
->setVisible(false);
329 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_COMBRIDGE
)) {
330 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
332 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_COMBRIDGE
)) {
333 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
335 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE
)) {
336 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
339 case HwSettings::RM_MAINPORT_DEBUGCONSOLE
:
340 m_ui
->lblMainSpeed
->setVisible(false);
341 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE
)) {
342 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
344 if (isComboboxOptionSelected(m_ui
->cbUSBVCPFunction
, HwSettings::USB_VCPPORT_DEBUGCONSOLE
)) {
345 setComboboxSelectedOption(m_ui
->cbUSBVCPFunction
, HwSettings::USB_VCPPORT_DISABLED
);
347 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE
)) {
348 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
350 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DEBUGCONSOLE
)) {
351 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
354 case HwSettings::RM_MAINPORT_OSDHK
:
355 m_ui
->lblMainSpeed
->setVisible(false);
356 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_OSDHK
)) {
357 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
360 case HwSettings::RM_MAINPORT_MSP
:
361 m_ui
->lblMainSpeed
->setVisible(false);
362 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_MSP
)) {
363 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
365 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_MSP
)) {
366 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
368 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMMSP
)) {
369 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
372 case HwSettings::RM_MAINPORT_MAVLINK
:
373 m_ui
->lblMainSpeed
->setVisible(false);
374 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_MAVLINK
)) {
375 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
377 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_MAVLINK
)) {
378 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_DISABLED
);
380 if (isComboboxOptionSelected(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPMMAVLINK
)) {
381 setComboboxSelectedOption(m_ui
->cbRcvr
, HwSettings::RM_RCVRPORT_PPM
);
385 m_ui
->lblMainSpeed
->setVisible(false);
390 void ConfigRevoHWWidget::rcvrPortChanged(int index
)
393 m_ui
->lblRcvrSpeed
->setVisible(true);
394 m_ui
->cbRcvrTelemSpeed
->setVisible(false);
395 m_ui
->cbRcvrGPSSpeed
->setVisible(false);
397 // Add Gps protocol configuration
398 m_ui
->cbRcvrGPSProtocol
->setVisible(false);
399 m_ui
->lblRcvrGPSProtocol
->setVisible(false);
401 switch (getComboboxSelectedOption(m_ui
->cbRcvr
)) {
402 case HwSettings::RM_RCVRPORT_TELEMETRY
:
403 case HwSettings::RM_RCVRPORT_PPMTELEMETRY
:
404 m_ui
->cbRcvrTelemSpeed
->setVisible(true);
406 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_TELEMETRY
)) {
407 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
409 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_TELEMETRY
)) {
410 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
413 case HwSettings::RM_RCVRPORT_COMBRIDGE
:
414 case HwSettings::RM_RCVRPORT_PPMCOMBRIDGE
:
415 m_ui
->lblRcvrSpeed
->setVisible(false);
416 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_COMBRIDGE
)) {
417 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
419 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_COMBRIDGE
)) {
420 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
423 case HwSettings::RM_RCVRPORT_DEBUGCONSOLE
:
424 case HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE
:
425 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE
)) {
426 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
428 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DEBUGCONSOLE
)) {
429 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
432 case HwSettings::RM_RCVRPORT_GPS
:
433 case HwSettings::RM_RCVRPORT_PPMGPS
:
434 // Add Gps protocol configuration
435 m_ui
->cbRcvrGPSProtocol
->setVisible(true);
436 m_ui
->lblRcvrGPSProtocol
->setVisible(true);
438 m_ui
->cbRcvrGPSSpeed
->setVisible(true);
440 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_GPS
)) {
441 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
443 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_GPS
)) {
444 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
447 case HwSettings::RM_RCVRPORT_MSP
:
448 case HwSettings::RM_RCVRPORT_PPMMSP
:
449 m_ui
->lblRcvrSpeed
->setVisible(false);
450 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_MSP
)) {
451 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
453 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_MSP
)) {
454 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
457 case HwSettings::RM_RCVRPORT_MAVLINK
:
458 case HwSettings::RM_RCVRPORT_PPMMAVLINK
:
459 m_ui
->lblRcvrSpeed
->setVisible(false);
460 if (isComboboxOptionSelected(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_MAVLINK
)) {
461 setComboboxSelectedOption(m_ui
->cbFlexi
, HwSettings::RM_FLEXIPORT_DISABLED
);
463 if (isComboboxOptionSelected(m_ui
->cbMain
, HwSettings::RM_MAINPORT_MAVLINK
)) {
464 setComboboxSelectedOption(m_ui
->cbMain
, HwSettings::RM_MAINPORT_DISABLED
);
468 m_ui
->lblRcvrSpeed
->setVisible(false);