diff --git a/flight/Bootloaders/BootloaderUpdater/main.c b/flight/Bootloaders/BootloaderUpdater/main.c
index b7348dac4..ff2c5ae2e 100644
--- a/flight/Bootloaders/BootloaderUpdater/main.c
+++ b/flight/Bootloaders/BootloaderUpdater/main.c
@@ -34,7 +34,7 @@
/* Prototype of PIOS_Board_Init() function */
extern void PIOS_Board_Init(void);
extern void FLASH_Download();
-void error(int);
+void error(int, int);
/* The ADDRESSES of the _binary_* symbols are the important
* data. This is non-intuitive for _binary_size where you
@@ -47,7 +47,8 @@ const uint32_t * embedded_image_start = (uint32_t *) &(_binary_start);
const uint32_t * embedded_image_end = (uint32_t *) &(_binary_end);
const uint32_t embedded_image_size = (uint32_t) &(_binary_size);
-int main() {
+int main()
+{
PIOS_SYS_Init();
PIOS_Board_Init();
@@ -58,7 +59,7 @@ int main() {
/// Self overwrite check
uint32_t base_address = SCB->VTOR;
if ((0x08000000 + embedded_image_size) > base_address)
- error(PIOS_LED_HEARTBEAT);
+ error(PIOS_LED_HEARTBEAT, 1);
///
/*
@@ -70,7 +71,7 @@ int main() {
*/
/* Calculate how far the board_info_blob is from the beginning of the bootloader */
- uint32_t board_info_blob_offset = (uint32_t)&pios_board_info_blob - (uint32_t)0x08000000;
+ uint32_t board_info_blob_offset = (uint32_t) &pios_board_info_blob - (uint32_t)0x08000000;
/* Use the same offset into our embedded bootloader image */
struct pios_board_info * new_board_info_blob = (struct pios_board_info *)
@@ -80,7 +81,7 @@ int main() {
if ((pios_board_info_blob.magic != new_board_info_blob->magic) ||
(pios_board_info_blob.board_type != new_board_info_blob->board_type) ||
(pios_board_info_blob.board_rev != new_board_info_blob->board_rev)) {
- error(PIOS_LED_HEARTBEAT);
+ error(PIOS_LED_HEARTBEAT, 2);
}
/* Embedded bootloader looks like it's the right one for this HW, proceed... */
@@ -108,30 +109,30 @@ int main() {
}
if (fail == true)
- error(PIOS_LED_HEARTBEAT);
+ error(PIOS_LED_HEARTBEAT, 3);
///
/// Bootloader programing
- for (uint32_t offset = 0; offset < embedded_image_size/sizeof(uint32_t); ++offset) {
+ for (uint32_t offset = 0; offset < embedded_image_size / sizeof(uint32_t); ++offset) {
bool result = false;
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
for (uint8_t retry = 0; retry < MAX_WRI_RETRYS; ++retry) {
if (result == false) {
result = (FLASH_ProgramWord(0x08000000 + (offset * 4), embedded_image_start[offset])
- == FLASH_COMPLETE) ? true : false;
+ == FLASH_COMPLETE) ? true : false;
}
}
if (result == false)
- error(PIOS_LED_HEARTBEAT);
+ error(PIOS_LED_HEARTBEAT, 4);
}
///
for (uint8_t x = 0; x < 3; ++x) {
- PIOS_LED_On(PIOS_LED_HEARTBEAT);
- PIOS_DELAY_WaitmS(1000);
- PIOS_LED_Off(PIOS_LED_HEARTBEAT);
- PIOS_DELAY_WaitmS(1000);
+ PIOS_LED_On(PIOS_LED_HEARTBEAT);
+ PIOS_DELAY_WaitmS(1000);
+ PIOS_LED_Off(PIOS_LED_HEARTBEAT);
+ PIOS_DELAY_WaitmS(1000);
}
/// Invalidate the bootloader updater so we won't run
@@ -145,11 +146,22 @@ int main() {
}
-void error(int led) {
+void error(int led, int code)
+{
for (;;) {
- PIOS_LED_On(led);
- PIOS_DELAY_WaitmS(500);
- PIOS_LED_Off(led);
- PIOS_DELAY_WaitmS(500);
+ PIOS_DELAY_WaitmS(1000);
+ for (int x = 0; x < code; x++) {
+ PIOS_LED_On(led);
+ PIOS_DELAY_WaitmS(200);
+ PIOS_LED_Off(led);
+ PIOS_DELAY_WaitmS(1000);
+ }
+ PIOS_DELAY_WaitmS(1000);
+ for (int x = 0; x < 10; x++) {
+ PIOS_LED_On(led);
+ PIOS_DELAY_WaitmS(200);
+ PIOS_LED_Off(led);
+ PIOS_DELAY_WaitmS(200);
+ }
}
-}
+}
\ No newline at end of file
diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui
index c2d2db6e4..e70184c17 100755
--- a/ground/openpilotgcs/src/plugins/config/airframe.ui
+++ b/ground/openpilotgcs/src/plugins/config/airframe.ui
@@ -128,8 +128,8 @@
0
0
- 850
- 508
+ 852
+ 518
@@ -215,7 +215,7 @@
QFrame::NoFrame
- 1
+ 4
@@ -703,7 +703,7 @@ margin:1px;
0
- -1
+ 6
-
@@ -1555,8 +1555,8 @@ margin:1px;
0
0
- 800
- 386
+ 808
+ 397
@@ -2158,6 +2158,9 @@ margin:1px;
true
+
+ 12
+
50
@@ -2244,6 +2247,16 @@ margin:1px;
Ch 10
+
+
+ Ch 11
+
+
+
+
+ Ch 12
+
+
-
-
@@ -2324,6 +2337,24 @@ margin:1px;
AlignHCenter|AlignVCenter|AlignCenter
+
+ -
+
+ -
+
+
+ AlignHCenter|AlignVCenter|AlignCenter
+
+
+ -
+
+ -
+
+
+ AlignHCenter|AlignVCenter|AlignCenter
+
+
+
-
-
@@ -2404,6 +2435,23 @@ margin:1px;
AlignHCenter|AlignVCenter|AlignCenter
+ -
+
+ -
+
+
+ AlignHCenter|AlignVCenter|AlignCenter
+
+
+ -
+
+ -
+
+
+ AlignHCenter|AlignVCenter|AlignCenter
+
+
+
-
-
@@ -2484,6 +2532,23 @@ margin:1px;
AlignHCenter|AlignVCenter|AlignCenter
+
+ -
+
+ -
+
+
+ AlignHCenter|AlignVCenter|AlignCenter
+
+
+ -
+
+ -
+
+
+ AlignHCenter|AlignVCenter|AlignCenter
+
+
-
-
@@ -2564,6 +2629,24 @@ margin:1px;
AlignHCenter|AlignVCenter|AlignCenter
+
+ -
+
+ -
+
+
+ AlignHCenter|AlignVCenter|AlignCenter
+
+
+ -
+
+ -
+
+
+ AlignHCenter|AlignVCenter|AlignCenter
+
+
+
-
-
@@ -2644,6 +2727,23 @@ margin:1px;
AlignHCenter|AlignVCenter|AlignCenter
+
+ -
+
+ -
+
+
+ AlignHCenter|AlignVCenter|AlignCenter
+
+
+ -
+
+ -
+
+
+ AlignHCenter|AlignVCenter|AlignCenter
+
+
-
-
@@ -2724,6 +2824,24 @@ margin:1px;
AlignHCenter|AlignVCenter|AlignCenter
+
+ -
+
+ -
+
+
+ AlignHCenter|AlignVCenter|AlignCenter
+
+
+ -
+
+ -
+
+
+ AlignHCenter|AlignVCenter|AlignCenter
+
+
+
@@ -2832,8 +2950,8 @@ margin:1px;
0
0
- 287
- 326
+ 852
+ 518
@@ -3216,15 +3334,15 @@ p, li { white-space: pre-wrap; }
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;">
+</style></head><body style=" font-family:'Ubuntu'; font-size:9pt; font-weight:400; font-style:normal;">
<table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;">
<tr>
<td style="border: none;">
-<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD REQUIRES CAUTION</span></p>
-<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;"><br /></span></p>
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</p>
-<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</p></td></tr></table></body></html>
+<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD REQUIRES CAUTION</span></p>
+<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:11pt;"><br /></p>
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:11pt;"><br /></span></p>
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</span></p>
+<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</span></p></td></tr></table></body></html>
diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h
index 5f47d0548..68d930305 100644
--- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h
+++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h
@@ -31,6 +31,7 @@
#include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h"
#include "uavobject.h"
+#include "actuatorcommand.h"
typedef struct {
@@ -144,7 +145,7 @@ class VehicleConfig: public ConfigTaskWidget
QStringList mixerVectors;
QStringList mixerTypeDescriptions;
- static const quint32 CHANNEL_NUMELEM = 10;
+ static const quint32 CHANNEL_NUMELEM = ActuatorCommand::CHANNEL_NUMELEM;
private:
diff --git a/ground/openpilotgcs/src/plugins/config/config.pro b/ground/openpilotgcs/src/plugins/config/config.pro
index af6f3e1ed..d36c2b2a9 100644
--- a/ground/openpilotgcs/src/plugins/config/config.pro
+++ b/ground/openpilotgcs/src/plugins/config/config.pro
@@ -17,7 +17,6 @@ HEADERS += configplugin.h \
configinputwidget.h \
configoutputwidget.h \
configvehicletypewidget.h \
- config_pro_hw_widget.h \
config_cc_hw_widget.h \
configccattitudewidget.h \
configpipxtremewidget.h \
@@ -38,7 +37,8 @@ HEADERS += configplugin.h \
configrevowidget.h \
config_global.h \
mixercurve.h \
- dblspindelegate.h
+ dblspindelegate.h \
+ configrevohwwidget.h
SOURCES += configplugin.cpp \
configgadgetconfiguration.cpp \
configgadgetwidget.cpp \
@@ -49,7 +49,6 @@ SOURCES += configplugin.cpp \
configinputwidget.cpp \
configoutputwidget.cpp \
configvehicletypewidget.cpp \
- config_pro_hw_widget.cpp \
config_cc_hw_widget.cpp \
configccattitudewidget.cpp \
configstabilizationwidget.cpp \
@@ -71,10 +70,10 @@ SOURCES += configplugin.cpp \
outputchannelform.cpp \
cfg_vehicletypes/vehicleconfig.cpp \
mixercurve.cpp \
- dblspindelegate.cpp
+ dblspindelegate.cpp \
+ configrevohwwidget.cpp
FORMS += airframe.ui \
cc_hw_settings.ui \
- pro_hw_settings.ui \
ccpm.ui \
stabilization.ui \
input.ui \
@@ -88,5 +87,13 @@ FORMS += airframe.ui \
revosensors.ui \
txpid.ui \
pipxtreme.ui \
- mixercurve.ui
+ mixercurve.ui \
+ configrevohwwidget.ui
RESOURCES += configgadget.qrc
+
+
+
+
+
+
+
diff --git a/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp
deleted file mode 100644
index 0f050cbc2..000000000
--- a/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp
+++ /dev/null
@@ -1,60 +0,0 @@
-/**
- ******************************************************************************
- *
- * @file configtelemetrywidget.h
- * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
- * @addtogroup GCSPlugins GCS Plugins
- * @{
- * @addtogroup ConfigPlugin Config Plugin
- * @{
- * @brief The Configuration Gadget used to update settings in the firmware
- *****************************************************************************/
-/*
- * This program 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.
- *
- * This program 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 this program; if not, write to the Free Software Foundation, Inc.,
- * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
- */
-#include "config_pro_hw_widget.h"
-
-#include
-#include
-#include
-#include
-#include
-#include
-
-
-ConfigProHWWidget::ConfigProHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
-{
- m_telemetry = new Ui_PRO_HW_Widget();
- m_telemetry->setupUi(this);
-
- addApplySaveButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
- addUAVObjectToWidgetRelation("HwSettings","TelemetrySpeed",m_telemetry->telemetrySpeed);
- enableControls(false);
- populateWidgets();
- refreshWidgetsValues(NULL);
-}
-
-ConfigProHWWidget::~ConfigProHWWidget()
-{
- // Do nothing
-}
-
-
-/**
- Request telemetry settings from the board
- */
-void ConfigProHWWidget::refreshValues()
-{
-}
diff --git a/ground/openpilotgcs/src/plugins/config/configgadget.qrc b/ground/openpilotgcs/src/plugins/config/configgadget.qrc
index ff81d79fb..a5b006745 100644
--- a/ground/openpilotgcs/src/plugins/config/configgadget.qrc
+++ b/ground/openpilotgcs/src/plugins/config/configgadget.qrc
@@ -30,5 +30,6 @@
images/camstab_normal.png
images/pipx-selected.png
images/pipx-normal.png
+ images/revolution_top.png
diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp
index ad2b9ed8a..ab50ffbdc 100644
--- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp
+++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp
@@ -34,7 +34,7 @@
#include "configstabilizationwidget.h"
#include "configcamerastabilizationwidget.h"
#include "configtxpidwidget.h"
-#include "config_pro_hw_widget.h"
+#include "configrevohwwidget.h"
#include "config_cc_hw_widget.h"
#include "configpipxtremewidget.h"
#include "configrevowidget.h"
@@ -129,7 +129,7 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
}
help = 0;
- connect(ftw,SIGNAL(currentAboutToShow(int,bool*)),this,SLOT(tabAboutToChange(int,bool*)));//,Qt::BlockingQueuedConnection);
+ connect(ftw,SIGNAL(currentAboutToShow(int,bool*)), this, SLOT(tabAboutToChange(int,bool*)));
// Connect to the PipXStatus object updates
UAVObjectManager *objManager = pm->getObject();
@@ -166,20 +166,21 @@ void ConfigGadgetWidget::resizeEvent(QResizeEvent *event)
void ConfigGadgetWidget::onAutopilotDisconnect() {
ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
- ftw->removeTab(ConfigGadgetWidget::sensors);
QIcon *icon = new QIcon();
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new DefaultAttitudeWidget(this);
+ ftw->removeTab(ConfigGadgetWidget::sensors);
ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS"));
- ftw->removeTab(ConfigGadgetWidget::hardware);
icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new DefaultHwSettingsWidget(this);
+ ftw->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
+
ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
emit autopilotDisconnected();
@@ -196,40 +197,39 @@ void ConfigGadgetWidget::onAutopilotConnect() {
int board = utilMngr->getBoardModel();
if ((board & 0xff00) == 1024) {
// CopterControl family
- // Delete the INS panel, replace with CC Panel:
- ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
- ftw->removeTab(ConfigGadgetWidget::sensors);
QIcon *icon = new QIcon();
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new ConfigCCAttitudeWidget(this);
- ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS"));
- ftw->removeTab(ConfigGadgetWidget::hardware);
+ ftw->removeTab(ConfigGadgetWidget::sensors);
+ ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("CopterControl"));
icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off);
qwd = new ConfigCCHWWidget(this);
+ ftw->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
+
ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
} else if ((board & 0xff00) == 0x0900) {
- // Revolution sensor calibration
- ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
- ftw->removeTab(ConfigGadgetWidget::sensors);
+ // Revolution family
QIcon *icon = new QIcon();
icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off);
icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off);
QWidget *qwd = new ConfigRevoWidget(this);
- ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Revo"));
- ftw->removeTab(ConfigGadgetWidget::hardware);
+ ftw->removeTab(ConfigGadgetWidget::sensors);
+ ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Revolution"));
icon = new QIcon();
icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off);
- icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Normal, QIcon::On);
- qwd = new ConfigProHWWidget(this);
+ icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off);
+ qwd = new ConfigRevoHWWidget(this);
+ ftw->removeTab(ConfigGadgetWidget::hardware);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware"));
+
ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
} else {
//Unknown board
diff --git a/ground/openpilotgcs/src/plugins/config/configrevohwwidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.cpp
new file mode 100644
index 000000000..6564819a7
--- /dev/null
+++ b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.cpp
@@ -0,0 +1,297 @@
+/**
+ ******************************************************************************
+ *
+ * @file configrevohwwidget.cpp
+ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
+ * @addtogroup GCSPlugins GCS Plugins
+ * @{
+ * @addtogroup ConfigPlugin Config Plugin
+ * @{
+ * @brief Revolution hardware configuration panel
+ *****************************************************************************/
+/*
+ * This program 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.
+ *
+ * This program 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 this program; if not, write to the Free Software Foundation, Inc.,
+ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
+ */
+#include "configrevohwwidget.h"
+
+#include
+#include
+#include
+#include "hwsettings.h"
+#include
+#include
+
+
+ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
+{
+ m_ui = new Ui_RevoHWWidget();
+ m_ui->setupUi(this);
+
+ ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
+ Core::Internal::GeneralSettings *settings = pm->getObject();
+ if(!settings->useExpertMode()) {
+ m_ui->saveTelemetryToRAM->setEnabled(false);
+ m_ui->saveTelemetryToRAM->setVisible(false);
+ }
+
+ addApplySaveButtons(m_ui->saveTelemetryToRAM, m_ui->saveTelemetryToSD);
+
+ addUAVObjectToWidgetRelation("HwSettings","RM_FlexiPort",m_ui->cbFlexi);
+ addUAVObjectToWidgetRelation("HwSettings","RM_MainPort",m_ui->cbMain);
+ addUAVObjectToWidgetRelation("HwSettings","RM_RcvrPort",m_ui->cbRcvr);
+
+ addUAVObjectToWidgetRelation("HwSettings","USB_HIDPort",m_ui->cbUSBHIDFunction);
+ addUAVObjectToWidgetRelation("HwSettings","USB_VCPPort",m_ui->cbUSBVCPFunction);
+ addUAVObjectToWidgetRelation("HwSettings","ComUsbBridgeSpeed",m_ui->cbUSBVCPSpeed);
+
+ addUAVObjectToWidgetRelation("HwSettings","TelemetrySpeed",m_ui->cbFlexiTelemSpeed);
+ addUAVObjectToWidgetRelation("HwSettings","GPSSpeed",m_ui->cbFlexiGPSSpeed);
+ addUAVObjectToWidgetRelation("HwSettings","ComUsbBridgeSpeed",m_ui->cbFlexiComSpeed);
+
+ addUAVObjectToWidgetRelation("HwSettings","TelemetrySpeed",m_ui->cbMainTelemSpeed);
+ addUAVObjectToWidgetRelation("HwSettings","GPSSpeed",m_ui->cbMainGPSSpeed);
+ addUAVObjectToWidgetRelation("HwSettings","ComUsbBridgeSpeed",m_ui->cbMainComSpeed);
+
+ addUAVObjectToWidgetRelation("HwSettings","RadioPort",m_ui->cbModem);
+
+ connect(m_ui->cchwHelp,SIGNAL(clicked()),this,SLOT(openHelp()));
+
+ setupCustomCombos();
+ enableControls(true);
+ populateWidgets();
+ refreshWidgetsValues();
+ forceConnectedState();
+}
+
+ConfigRevoHWWidget::~ConfigRevoHWWidget()
+{
+ // Do nothing
+}
+
+void ConfigRevoHWWidget::setupCustomCombos()
+{
+ connect(m_ui->cbUSBHIDFunction, SIGNAL(currentIndexChanged(int)), this, SLOT(usbHIDPortChanged(int)));
+ connect(m_ui->cbUSBVCPFunction, SIGNAL(currentIndexChanged(int)), this, SLOT(usbVCPPortChanged(int)));
+
+ m_ui->cbSonar->addItem(tr("Disabled"));
+ m_ui->cbSonar->setCurrentIndex(0);
+ m_ui->cbSonar->setEnabled(false);
+
+ connect(m_ui->cbFlexi, SIGNAL(currentIndexChanged(int)), this, SLOT(flexiPortChanged(int)));
+ connect(m_ui->cbMain, SIGNAL(currentIndexChanged(int)), this, SLOT(mainPortChanged(int)));
+ connect(m_ui->cbModem, SIGNAL(currentIndexChanged(int)), this, SLOT(modemPortChanged(int)));
+
+}
+
+void ConfigRevoHWWidget::refreshWidgetsValues(UAVObject *obj)
+{
+ ConfigTaskWidget::refreshWidgetsValues(obj);
+ usbVCPPortChanged(0);
+ mainPortChanged(0);
+ flexiPortChanged(0);
+}
+
+void ConfigRevoHWWidget::updateObjectsFromWidgets()
+{
+ ConfigTaskWidget::updateObjectsFromWidgets();
+
+ HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager());
+ HwSettings::DataFields data = hwSettings->getData();
+
+ // If any port is configured to be GPS port, enable GPS module if it is not enabled.
+ // Otherwise disable GPS module.
+ if(m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_GPS || m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_GPS) {
+ data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_ENABLED;
+ }
+ else {
+ data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_DISABLED;
+ }
+
+ // If any port is configured to be ComBridge port, enable UsbComBridge module if it is not enabled.
+ // Otherwise disable UsbComBridge module.
+ if(m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_COMBRIDGE || m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_COMBRIDGE ||
+ m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_COMBRIDGE) {
+ data.OptionalModules[HwSettings::OPTIONALMODULES_COMUSBBRIDGE] = HwSettings::OPTIONALMODULES_ENABLED;
+ }
+ else {
+ data.OptionalModules[HwSettings::OPTIONALMODULES_COMUSBBRIDGE] = HwSettings::OPTIONALMODULES_DISABLED;
+ }
+
+ hwSettings->setData(data);
+}
+
+void ConfigRevoHWWidget::usbVCPPortChanged(int index)
+{
+ Q_UNUSED(index);
+
+ bool vcpComBridgeEnabled = m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_COMBRIDGE;
+
+ m_ui->lblUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
+ m_ui->cbUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
+
+ if(!vcpComBridgeEnabled && m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_COMBRIDGE) {
+ m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
+ }
+ m_ui->cbFlexi->model()->setData(m_ui->cbFlexi->model()->index(HwSettings::RM_FLEXIPORT_COMBRIDGE, 0),
+ !vcpComBridgeEnabled ? QVariant(0) : QVariant(1|32), Qt::UserRole - 1);
+
+ if(!vcpComBridgeEnabled && m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_COMBRIDGE) {
+ m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
+ }
+ m_ui->cbMain->model()->setData(m_ui->cbMain->model()->index(HwSettings::RM_MAINPORT_COMBRIDGE, 0),
+ !vcpComBridgeEnabled ? QVariant(0) : QVariant(1|32), Qt::UserRole - 1);
+
+ //_DEBUGCONSOLE modes are mutual exclusive
+ if(m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE) {
+ if(m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_DEBUGCONSOLE) {
+ m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
+ }
+ if(m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_DEBUGCONSOLE) {
+ m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
+ }
+ }
+
+ //_USBTELEMETRY modes are mutual exclusive
+ if(m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_USBTELEMETRY) {
+ if(m_ui->cbUSBHIDFunction->currentIndex() == HwSettings::USB_HIDPORT_USBTELEMETRY) {
+ m_ui->cbUSBHIDFunction->setCurrentIndex(HwSettings::USB_HIDPORT_DISABLED);
+ }
+ }
+}
+
+void ConfigRevoHWWidget::usbHIDPortChanged(int index)
+{
+ Q_UNUSED(index);
+
+ //_USBTELEMETRY modes are mutual exclusive
+ if(m_ui->cbUSBHIDFunction->currentIndex() == HwSettings::USB_HIDPORT_USBTELEMETRY) {
+ if(m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_USBTELEMETRY) {
+ m_ui->cbUSBVCPFunction->setCurrentIndex(HwSettings::USB_VCPPORT_DISABLED);
+ }
+ }
+}
+
+void ConfigRevoHWWidget::flexiPortChanged(int index)
+{
+ Q_UNUSED(index);
+
+ m_ui->cbFlexiTelemSpeed->setVisible(false);
+ m_ui->cbFlexiGPSSpeed->setVisible(false);
+ m_ui->cbFlexiComSpeed->setVisible(false);
+ m_ui->lblFlexiSpeed->setVisible(true);
+
+ switch(m_ui->cbFlexi->currentIndex())
+ {
+ case HwSettings::RM_FLEXIPORT_TELEMETRY:
+ m_ui->cbFlexiTelemSpeed->setVisible(true);
+ if(m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_TELEMETRY) {
+ m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
+ }
+ if(m_ui->cbModem->currentIndex() == HwSettings::RADIOPORT_TELEMETRY) {
+ m_ui->cbModem->setCurrentIndex(HwSettings::RADIOPORT_DISABLED);
+ }
+ break;
+ case HwSettings::RM_FLEXIPORT_GPS:
+ m_ui->cbFlexiGPSSpeed->setVisible(true);
+ if(m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_GPS) {
+ m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
+ }
+ break;
+ case HwSettings::RM_FLEXIPORT_COMBRIDGE:
+ m_ui->cbFlexiComSpeed->setVisible(true);
+ if(m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_COMBRIDGE) {
+ m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
+ }
+ break;
+ case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE:
+ m_ui->cbFlexiComSpeed->setVisible(true);
+ if(m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_DEBUGCONSOLE) {
+ m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
+ }
+ if(m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE) {
+ m_ui->cbUSBVCPFunction->setCurrentIndex(HwSettings::USB_VCPPORT_DISABLED);
+ }
+ break;
+ default:
+ m_ui->lblFlexiSpeed->setVisible(false);
+ break;
+ }
+}
+
+void ConfigRevoHWWidget::mainPortChanged(int index)
+{
+ Q_UNUSED(index);
+
+ m_ui->cbMainTelemSpeed->setVisible(false);
+ m_ui->cbMainGPSSpeed->setVisible(false);
+ m_ui->cbMainComSpeed->setVisible(false);
+ m_ui->lblMainSpeed->setVisible(true);
+
+ switch(m_ui->cbMain->currentIndex())
+ {
+ case HwSettings::RM_MAINPORT_TELEMETRY:
+ m_ui->cbMainTelemSpeed->setVisible(true);
+ if(m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
+ m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
+ }
+ if(m_ui->cbModem->currentIndex() == HwSettings::RADIOPORT_TELEMETRY) {
+ m_ui->cbModem->setCurrentIndex(HwSettings::RADIOPORT_DISABLED);
+ }
+ break;
+ case HwSettings::RM_MAINPORT_GPS:
+ m_ui->cbMainGPSSpeed->setVisible(true);
+ if(m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_GPS) {
+ m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
+ }
+ break;
+ case HwSettings::RM_MAINPORT_COMBRIDGE:
+ m_ui->cbMainComSpeed->setVisible(true);
+ if(m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_COMBRIDGE) {
+ m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
+ }
+ break;
+ case HwSettings::RM_MAINPORT_DEBUGCONSOLE:
+ m_ui->cbMainComSpeed->setVisible(true);
+ if(m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_DEBUGCONSOLE) {
+ m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
+ }
+ if(m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE) {
+ m_ui->cbUSBVCPFunction->setCurrentIndex(HwSettings::USB_VCPPORT_DISABLED);
+ }
+ break;
+ default:
+ m_ui->lblMainSpeed->setVisible(false);
+ break;
+ }
+}
+
+void ConfigRevoHWWidget::modemPortChanged(int index)
+{
+ Q_UNUSED(index);
+
+ if(m_ui->cbModem->currentIndex()== HwSettings::RADIOPORT_TELEMETRY) {
+ if(m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_TELEMETRY) {
+ m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
+ }
+ if(m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
+ m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
+ }
+ }
+}
+
+void ConfigRevoHWWidget::openHelp()
+{
+ QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/GgDBAQ", QUrl::StrictMode) );
+}
diff --git a/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.h b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.h
similarity index 64%
rename from ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.h
rename to ground/openpilotgcs/src/plugins/config/configrevohwwidget.h
index 021e19aaf..7e6ed51f4 100644
--- a/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.h
+++ b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.h
@@ -1,13 +1,13 @@
/**
******************************************************************************
*
- * @file configtelemetrytwidget.h
+ * @file configrevohwwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
- * @brief Telemetry configuration panel
+ * @brief Revolution hardware configuration panel
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
@@ -24,10 +24,10 @@
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
-#ifndef CONFIGPROHWWIDGET_H
-#define CONFIGPROHWWIDGET_H
+#ifndef CONFIGREVOHWWIDGET_H
+#define CONFIGREVOHWWIDGET_H
-#include "ui_pro_hw_settings.h"
+#include "ui_configrevohwwidget.h"
#include "../uavobjectwidgetutils/configtaskwidget.h"
#include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h"
@@ -36,20 +36,30 @@
#include
-class ConfigProHWWidget: public ConfigTaskWidget
+class ConfigRevoHWWidget: public ConfigTaskWidget
{
Q_OBJECT
public:
- ConfigProHWWidget(QWidget *parent = 0);
- ~ConfigProHWWidget();
+ ConfigRevoHWWidget(QWidget *parent = 0);
+ ~ConfigRevoHWWidget();
private:
- Ui_PRO_HW_Widget *m_telemetry;
+ Ui_RevoHWWidget *m_ui;
+ void setupCustomCombos();
+
+protected slots:
+ void refreshWidgetsValues(UAVObject * obj = NULL);
+ void updateObjectsFromWidgets();
private slots:
- virtual void refreshValues();
+ void usbVCPPortChanged(int index);
+ void usbHIDPortChanged(int index);
+ void flexiPortChanged(int index);
+ void mainPortChanged(int index);
+ void modemPortChanged(int index);
+ void openHelp();
};
-#endif // CONFIGPROHWWIDGET_H
+#endif // CONFIGREVOHWWIDGET_H
diff --git a/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui
new file mode 100644
index 000000000..199d2e817
--- /dev/null
+++ b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui
@@ -0,0 +1,865 @@
+
+
+ RevoHWWidget
+
+
+
+ 0
+ 0
+ 834
+ 742
+
+
+
+ Form
+
+
+ -
+
+
+ 0
+
+
+
+ HW settings
+
+
+
+ 0
+
+
-
+
+
+
+
+
+
+
+ 255
+ 255
+ 255
+
+
+
+
+
+
+ 232
+ 232
+ 232
+
+
+
+
+
+
+
+
+ 255
+ 255
+ 255
+
+
+
+
+
+
+ 232
+ 232
+ 232
+
+
+
+
+
+
+
+
+ 232
+ 232
+ 232
+
+
+
+
+
+
+ 232
+ 232
+ 232
+
+
+
+
+
+
+
+ border-color: rgb(255, 0, 0);
+
+
+ QFrame::NoFrame
+
+
+ QFrame::Plain
+
+
+ true
+
+
+
+
+ 0
+ 0
+ 810
+ 665
+
+
+
+
+ 12
+
+
-
+
+
-
+
+
+
+ 0
+ 0
+
+
+
+ USB VCP Function
+
+
+ Qt::AlignBottom|Qt::AlignHCenter
+
+
+
+ -
+
+
+ Speed
+
+
+ Qt::AlignBottom|Qt::AlignHCenter
+
+
+
+ -
+
+
+ false
+
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+ Speed
+
+
+ Qt::AlignBottom|Qt::AlignHCenter
+
+
+
+ -
+
+
+ -
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+ USB HID Function
+
+
+ Qt::AlignBottom|Qt::AlignHCenter
+
+
+
+ -
+
+
+ -
+
+
+ true
+
+
+
+ -
+
+
+ Main Port
+
+
+ Qt::AlignBottom|Qt::AlignHCenter
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+ QSizePolicy::Fixed
+
+
+
+ 50
+ 10
+
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+ QSizePolicy::Minimum
+
+
+
+ 120
+ 10
+
+
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+
+ 350
+ 350
+
+
+
+
+
+
+ :/configgadget/images/revolution_top.png
+
+
+ false
+
+
+ Qt::AlignCenter
+
+
+ Qt::NoTextInteraction
+
+
+
+ -
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+ Sonar Port
+
+
+ Qt::AlignBottom|Qt::AlignHCenter
+
+
+
+ -
+
+
+ -
+
+
+ 0
+
+
-
+
+
+ true
+
+
+
+ -
+
+
+ -
+
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+ QSizePolicy::Minimum
+
+
+
+ 120
+ 10
+
+
+
+
+ -
+
+
+ Flexi Port
+
+
+ Qt::AlignBottom|Qt::AlignHCenter
+
+
+
+ -
+
+
+ 0
+
+
-
+
+
+ true
+
+
+
+ -
+
+
+ -
+
+
+
+
+ -
+
+
+ -
+
+
+ Radio
+
+
+ Qt::AlignBottom|Qt::AlignHCenter
+
+
+
+ -
+
+
+ Speed
+
+
+ Qt::AlignBottom|Qt::AlignHCenter
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+ QSizePolicy::Minimum
+
+
+
+ 120
+ 10
+
+
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+ Receiver Port
+
+
+ Qt::AlignBottom|Qt::AlignHCenter
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+ QSizePolicy::Fixed
+
+
+
+ 20
+ 25
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+ QSizePolicy::Fixed
+
+
+
+ 20
+ 120
+
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+ QSizePolicy::Minimum
+
+
+
+ 120
+ 10
+
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+ QSizePolicy::Minimum
+
+
+
+ 120
+ 10
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+ QSizePolicy::Fixed
+
+
+
+ 20
+ 13
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+ QSizePolicy::Fixed
+
+
+
+ 20
+ 20
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+ QSizePolicy::Fixed
+
+
+
+ 20
+ 13
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+ QSizePolicy::Fixed
+
+
+
+ 20
+ 20
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+ QSizePolicy::Fixed
+
+
+
+ 20
+ 13
+
+
+
+
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+
+ 0
+ 0
+
+
+
+
+ 16777215
+ 16777215
+
+
+
+
+ 75
+ true
+
+
+
+ Changes on this page only take effect after board reset or power cycle
+
+
+ Qt::AlignCenter
+
+
+ true
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+ QSizePolicy::Fixed
+
+
+
+ 20
+ 10
+
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+
+
+ 4
+
+
-
+
+
+ Qt::Horizontal
+
+
+
+ 369
+ 20
+
+
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+
+ 25
+ 25
+
+
+
+
+ 25
+ 25
+
+
+
+ Takes you to the wiki page
+
+
+
+
+
+
+ :/core/images/helpicon.svg:/core/images/helpicon.svg
+
+
+
+ 25
+ 25
+
+
+
+ true
+
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+
+ 16777215
+ 16777215
+
+
+
+
+
+
+
+
+ 255
+ 255
+ 255
+
+
+
+
+
+
+ 232
+ 232
+ 232
+
+
+
+
+
+
+
+
+ 255
+ 255
+ 255
+
+
+
+
+
+
+ 232
+ 232
+ 232
+
+
+
+
+
+
+
+
+ 232
+ 232
+ 232
+
+
+
+
+
+
+ 232
+ 232
+ 232
+
+
+
+
+
+
+
+ Send to OpenPilot but don't write in SD.
+Beware of not locking yourself out!
+
+
+ false
+
+
+
+
+
+ Apply
+
+
+
+ 16
+ 16
+
+
+
+ false
+
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+
+ 16777215
+ 16777215
+
+
+
+ Applies and Saves all settings to SD.
+Beware of not locking yourself out!
+
+
+ false
+
+
+
+
+
+ Save
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp
index 99cfebdb4..dd290073a 100644
--- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp
+++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp
@@ -648,8 +648,8 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI()
m_aircraft->customThrottle2Curve->initLinearCurve(curveValues.count(), 1.0, m_aircraft->customThrottle2Curve->getMin());
}
- // Update the mixer table:
- for (int channel=0; channel<(int)(VehicleConfig::CHANNEL_NUMELEM); channel++) {
+ // Update the mixer table:
+ for (int channel=0; channel < m_aircraft->customMixerTable->columnCount(); channel++) {
UAVObjectField* field = mixer->getField(mixerTypes.at(channel));
if (field)
{
diff --git a/ground/openpilotgcs/src/plugins/config/images/revolution_top.png b/ground/openpilotgcs/src/plugins/config/images/revolution_top.png
new file mode 100644
index 000000000..a98e7e377
Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/revolution_top.png differ
diff --git a/ground/openpilotgcs/src/plugins/config/pro_hw_settings.ui b/ground/openpilotgcs/src/plugins/config/pro_hw_settings.ui
deleted file mode 100644
index 4c782357c..000000000
--- a/ground/openpilotgcs/src/plugins/config/pro_hw_settings.ui
+++ /dev/null
@@ -1,126 +0,0 @@
-
-
- PRO_HW_Widget
-
-
-
- 0
- 0
- 505
- 389
-
-
-
- Form
-
-
- -
-
-
- QFrame::StyledPanel
-
-
- QFrame::Raised
-
-
-
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Set the serial speed of your onboard telemetry modem here. It is the speed between the OpenPilot board and the onboard modem, and could be different from the radio link speed.</span></p>
-<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Sans'; font-size:10pt;"><br /></p>
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware of not locking yourself out! You should only modify this setting when the OpenPilot board is connected through the USB port.</span></p></body></html>
-
-
-
- -
-
-
-
-
-
-
- 11
- 75
- true
-
-
-
- Telemetry speed:
-
-
-
- -
-
-
- Select the speed here.
-
-
-
-
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 40
-
-
-
-
- -
-
-
- 4
-
-
-
-
-
- Qt::Horizontal
-
-
-
- 40
- 20
-
-
-
-
- -
-
-
- Send to OpenPilot but don't write in SD.
-Beware of not locking yourself out!
-
-
- Apply
-
-
-
- -
-
-
- Applies and Saves all settings to SD.
-Beware of not locking yourself out!
-
-
- Save
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp
index 000156d70..4cc506ab8 100644
--- a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp
+++ b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp
@@ -91,6 +91,7 @@ using namespace Core;
using namespace Core::Internal;
static const char *uriListMimeFormatC = "text/uri-list";
+static const char *DEFAULT_CONFIG_FILENAME = "OpenPilotGCS.xml";
enum { debugMainWindow = 0 };
@@ -267,7 +268,6 @@ void MainWindow::modeChanged(Core::IMode */*mode*/)
void MainWindow::extensionsInitialized()
{
QSettings *qs = m_settings;
- QSettings *settings;
QString commandLine;
if ( ! qs->allKeys().count() ) {
foreach(QString str, qApp->arguments()) {
@@ -288,28 +288,31 @@ void MainWindow::extensionsInitialized()
#endif
directory.cd("default_configurations");
- qDebug() << "Looking for default config files in: " + directory.absolutePath();
- bool showDialog = true;
+ qDebug() << "Looking for configuration files in:" << directory.absolutePath();
+
QString filename;
- if(!commandLine.isEmpty()) {
- if(QFile::exists(directory.absolutePath() + QDir::separator()+commandLine)) {
- filename = directory.absolutePath() + QDir::separator()+commandLine;
- qDebug() << "Load configuration from command line";
- settings = new QSettings(filename, XmlConfig::XmlSettingsFormat);
- showDialog = false;
- }
+ if(!commandLine.isEmpty() && QFile::exists(directory.absolutePath() + QDir::separator() + commandLine)) {
+ filename = directory.absolutePath() + QDir::separator() + commandLine;
+ qDebug() << "Configuration file" << filename << "specified on command line will be loaded.";
}
- if(showDialog) {
+ else if(QFile::exists(directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME)) {
+ filename = directory.absolutePath() + QDir::separator() + DEFAULT_CONFIG_FILENAME;
+ qDebug() << "Default configuration file" << filename << "will be loaded.";
+ }
+ else {
+ qDebug() << "Default configuration file " << directory.absolutePath() << QDir::separator() << DEFAULT_CONFIG_FILENAME << "was not found.";
importSettings *dialog = new importSettings(this);
dialog->loadFiles(directory.absolutePath());
dialog->exec();
filename = dialog->choosenConfig();
- settings = new QSettings(filename, XmlConfig::XmlSettingsFormat);
delete dialog;
+ qDebug() << "Configuration file" << filename << "was selected and will be loaded.";
}
- qs = settings;
- qDebug() << "Load default config from resource " << filename;
+
+ qs = new QSettings(filename, XmlConfig::XmlSettingsFormat);
+ qDebug() << "Configuration file" << filename << "was loaded.";
}
+
qs->beginGroup("General");
m_config_description=qs->value("Description", "none").toString();
m_config_details=qs->value("Details", "none").toString();
diff --git a/shared/uavobjectdefinition/actuatorcommand.xml b/shared/uavobjectdefinition/actuatorcommand.xml
index 17a7b7af5..7f8ce055e 100644
--- a/shared/uavobjectdefinition/actuatorcommand.xml
+++ b/shared/uavobjectdefinition/actuatorcommand.xml
@@ -1,7 +1,7 @@