diff --git a/CREDITS.txt b/CREDITS.txt index c39940316..3b3897b02 100644 --- a/CREDITS.txt +++ b/CREDITS.txt @@ -26,10 +26,11 @@ Joe Hlebasko Andy Honecker Ryan Hunt Mark James -Sami Korhonen -Thorsten Klose Ricky King +Thorsten Klose +Sami Korhonen Hallvard Kristiansen +Alan Krum Edouard Lafargue Mike Labranche Fredrik Larsson diff --git a/WHATSNEW.txt b/WHATSNEW.txt index 2b0d7e7c2..0c83c542e 100644 --- a/WHATSNEW.txt +++ b/WHATSNEW.txt @@ -1,4 +1,18 @@ ---- RELEASE-13.06 --- Italian Stallion Release --- +--- RELEASE-13.06.01 --- Italian Stallion Release --- +It applies the following changes to previously not released to public RELEASE-13.06 + +- Temporary disabled AltitudeHold and AltitudeVario flight modes. They were not +officially supported. But since people expected well-known production quality +behavior, it is better to make them final, then reenable +- Fix windows hid connection failure if board was already connected and gcs started; +- Fixed a bug that lead to disabled controls with some settings combination in CC/CC3D hardware page +- Fixed a bug that prevent to correct saving stabilization settings for CC/CC3D +- Fixes Uploader GUI and automatically close AutoUpdate panel after 7s + +JIRA issues addressed in this release: +OP-1028 OP-1020 OP-1024 + +--- RELEASE-13.06 --- This is the first official OpenPilot Revolution software release. This version also supports the CopterControl, CC3D, OPLinkMini and the upcoming OP OSD. @@ -133,14 +147,14 @@ KNOWN ISSUES: enabled, but you should properly calibrate them first. That's the reason why they are disabled by default. -- AltitudeHold mode is enabled, but it is not officially supported. Do +- AltitudeHold/Vario modes are enabled but not officially supported. Do not expect it to work perfectly and be considered production quality. You may play with it and report your issues and suggestions at your own risk. If you are not using a case for your Revo, we strongly recommend covering the barometer sensor with some foam to shield the sensor from wind and light. -- Note that throttle stick in AltitudeHold mode is used to control vertical +- Note that throttle stick in AltitudeVario mode is used to control vertical velocity, sometimes called vario altitude in other platforms, centre stick means hold altitude and there is a dead band around centre stick. @@ -175,17 +189,17 @@ Due to major rework of all code and integration of Revo code into mainline list above. Some of them can be found using this link: http://progress.openpilot.org/issues/?filter=10860 -OP-678, OP-693, OP-719, OP-726, OP-727, OP-747, OP-761, OP-769, OP-770, -OP-772, OP-784, OP-792, OP-804, OP-807, OP-812, OP-816, OP-817, OP-820, -OP-821, OP-843, OP-846, OP-854, OP-855, OP-856, OP-861, OP-864, OP-867, -OP-871, OP-873, OP-874, OP-875, OP-879, OP-885, OP-886, OP-888, OP-889, -OP-890, OP-891, OP-892, OP-893, OP-894, OP-895, OP-896, OP-897, OP-898, -OP-899, OP-900, OP-903, OP-905, OP-906, OP-907, OP-910, OP-912, OP-917, -OP-920, OP-925, OP-926, OP-928, OP-935, OP-936, OP-939, OP-952, OP-955, -OP-957, OP-958, OP-965, OP-968, OP-969, OP-970, OP-977, OP-979, OP-980, -OP-981, OP-982, OP-983, OP-988, OP-989, OP-990, OP-991, OP-993, OP-997, -OP-998, OP-999, OP-1000, OP-1002, OP-1005, OP-1007, OP-1008, OP-1009, OP-1010, -OP-1011, OP-1012, OP-1013, OP-1015, OP-1016, OP-1021 +OP-678, OP-682, OP-693, OP-719, OP-726, OP-727, OP-747, OP-761, OP-769, +OP-770, OP-772, OP-781, OP-784, OP-792, OP-804, OP-807, OP-812, OP-816, +OP-817, OP-820, OP-821, OP-834, OP-843, OP-846, OP-854, OP-855, OP-856, +OP-861, OP-864, OP-867, OP-871, OP-873, OP-874, OP-875, OP-879, OP-885, +OP-886, OP-888, OP-889, OP-890, OP-891, OP-892, OP-893, OP-894, OP-895, +OP-896, OP-897, OP-898, OP-899, OP-900, OP-903, OP-905, OP-906, OP-907, +OP-910, OP-912, OP-917, OP-920, OP-925, OP-926, OP-928, OP-935, OP-936, +OP-939, OP-952, OP-955, OP-957, OP-958, OP-965, OP-968, OP-969, OP-970, +OP-977, OP-979, OP-980, OP-981, OP-982, OP-983, OP-988, OP-989, OP-990, +OP-991, OP-993, OP-997, OP-998, OP-999, OP-1000, OP-1002, OP-1005, OP-1007, +OP-1008, OP-1009, OP-1010, OP-1011, OP-1012, OP-1013, OP-1015, OP-1016, OP-1021 Short summary of changes. For a complete list see the git log. @@ -214,7 +228,7 @@ Flight code changes: - added visualisation of errors in bootloader updater; - added numerous sanity checks to the flight code to prevent unsafe arming; - new flash file system, much faster and higly optimised; -- Revo settings are now stored in embedded MCU flash freeing up external one for flight logs; +- Revo data flash is splitted into two partitions, one for settings, another for user data (logs, etc); - OPLinkMini now stores settings in the MCU flash using FlashFS too; - a catalog of known flash types is used to support different flash types by the same firmware; - fixed broken overo submodule remote repository link; diff --git a/flight/targets/boards/revolution/board_hw_defs.c b/flight/targets/boards/revolution/board_hw_defs.c index e7b928d43..8b1dff63b 100644 --- a/flight/targets/boards/revolution/board_hw_defs.c +++ b/flight/targets/boards/revolution/board_hw_defs.c @@ -683,7 +683,7 @@ static const struct flashfs_logfs_cfg flashfs_external_user_cfg = { .arena_size = 0x00010000, /* 256 * slot size */ .slot_size = 0x00000100, /* 256 bytes */ - .start_offset = 0x40000, /* start at the beginning of the chip */ + .start_offset = 0x40000, /* start offset */ .sector_size = 0x00010000, /* 64K bytes */ .page_size = 0x00000100, /* 256 bytes */ }; diff --git a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp index f0762ff51..76f7fc5bb 100644 --- a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp @@ -84,7 +84,7 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent) addUAVObjectToWidgetRelation("HwSettings", "GPSSpeed", m_telemetry->gpsSpeed); addUAVObjectToWidgetRelation("HwSettings", "ComUsbBridgeSpeed", m_telemetry->comUsbBridgeSpeed); connect(m_telemetry->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - enableControls(false); + enableSaveButtons(false); populateWidgets(); refreshWidgetsValues(); forceConnectedState(); @@ -108,26 +108,32 @@ void ConfigCCHWWidget::widgetsContentsChanged() (m_telemetry->cbUsbVcp->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE)) || ((m_telemetry->cbUsbVcp->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE) && (m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_DEBUGCONSOLE))) { - enableControls(false); + enableSaveButtons(false); m_telemetry->problems->setText(tr("Warning: you have configured more than one DebugConsole, this currently is not supported")); } else if (((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_TELEMETRY) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_TELEMETRY)) || ((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_GPS) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_GPS)) || ((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_DEBUGCONSOLE) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_DEBUGCONSOLE)) || ((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_COMBRIDGE) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_COMBRIDGE))) { - enableControls(false); + enableSaveButtons(false); m_telemetry->problems->setText(tr("Warning: you have configured both MainPort and FlexiPort for the same function, this currently is not supported")); } else if ((m_telemetry->cbUsbHid->currentIndex() == HwSettings::USB_HIDPORT_USBTELEMETRY) && (m_telemetry->cbUsbVcp->currentIndex() == HwSettings::USB_VCPPORT_USBTELEMETRY)) { - enableControls(false); + enableSaveButtons(false); m_telemetry->problems->setText(tr("Warning: you have configured both USB HID Port and USB VCP Port for the same function, this currently is not supported")); } else if ((m_telemetry->cbUsbHid->currentIndex() != HwSettings::USB_HIDPORT_USBTELEMETRY) && (m_telemetry->cbUsbVcp->currentIndex() != HwSettings::USB_VCPPORT_USBTELEMETRY)) { - enableControls(false); + enableSaveButtons(false); m_telemetry->problems->setText(tr("Warning: you have disabled USB Telemetry on both USB HID Port and USB VCP Port, this currently is not supported")); } else { m_telemetry->problems->setText(""); - enableControls(true); + enableSaveButtons(true); } } +void ConfigCCHWWidget::enableSaveButtons(bool enable) +{ + m_telemetry->saveTelemetryToRAM->setEnabled(enable); + m_telemetry->saveTelemetryToSD->setEnabled(enable); +} + void ConfigCCHWWidget::openHelp() { QDesktopServices::openUrl(QUrl("http://wiki.openpilot.org/x/D4AUAQ", QUrl::StrictMode)); diff --git a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.h b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.h index 503955f0b..9acfa676e 100644 --- a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.h +++ b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.h @@ -46,6 +46,7 @@ private slots: void openHelp(); void refreshValues(); void widgetsContentsChanged(); + void enableSaveButtons(bool enable); private: Ui_CC_HW_Widget *m_telemetry; diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 013f82666..69df7ccc5 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -38,8 +38,10 @@ #include #include +#include "altitudeholdsettings.h" -ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) +ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent), + boardModel(0) { ui = new Ui_StabilizationWidget(); ui->setupUi(this); @@ -198,7 +200,17 @@ void ConfigStabilizationWidget::onBoardConnected() UAVObjectUtilManager *utilMngr = pm->getObject(); Q_ASSERT(utilMngr); - + boardModel = utilMngr->getBoardModel(); // If Revolution board enable misc tab, otherwise disable it - ui->AltitudeHold->setEnabled((utilMngr->getBoardModel() & 0xff00) == 0x0900); + ui->AltitudeHold->setEnabled((boardModel & 0xff00) == 0x0900); +} + +bool ConfigStabilizationWidget::shouldObjectBeSaved(UAVObject *object) +{ + // AltitudeHoldSettings should only be saved for Revolution board to avoid error. + if ((boardModel & 0xff00) != 0x0900) { + return dynamic_cast(object) == 0; + } else { + return true; + } } diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h index 0a783f4c5..c13448078 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h @@ -43,6 +43,7 @@ class ConfigStabilizationWidget : public ConfigTaskWidget { public: ConfigStabilizationWidget(QWidget *parent = 0); ~ConfigStabilizationWidget(); + bool shouldObjectBeSaved(UAVObject *object); private: Ui_StabilizationWidget *ui; @@ -51,6 +52,8 @@ private: // Milliseconds between automatic 'Instant Updates' static const int AUTOMATIC_UPDATE_RATE = 500; + int boardModel; + protected slots: void refreshWidgetsValues(UAVObject *o = NULL); diff --git a/ground/openpilotgcs/src/plugins/ophid/hidapi/windows/hid.c b/ground/openpilotgcs/src/plugins/ophid/hidapi/windows/hid.c index 9b85b19bb..0b561a2b2 100644 --- a/ground/openpilotgcs/src/plugins/ophid/hidapi/windows/hid.c +++ b/ground/openpilotgcs/src/plugins/ophid/hidapi/windows/hid.c @@ -219,9 +219,7 @@ static HANDLE open_device(const char *path, BOOL enumerate) { HANDLE handle; DWORD desired_access = (enumerate)? 0: (GENERIC_WRITE | GENERIC_READ); - DWORD share_mode = (enumerate)? - FILE_SHARE_READ|FILE_SHARE_WRITE: - FILE_SHARE_READ; + DWORD share_mode = FILE_SHARE_READ | FILE_SHARE_WRITE; handle = CreateFileA(path, desired_access, @@ -230,7 +228,7 @@ static HANDLE open_device(const char *path, BOOL enumerate) OPEN_EXISTING, FILE_FLAG_OVERLAPPED,/*FILE_ATTRIBUTE_NORMAL,*/ 0); - + DWORD error = GetLastError(); return handle; } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 2f007eec0..df6cf2236 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -413,7 +413,7 @@ void ConfigTaskWidget::helpButtonPressed() void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save) { if (!smartsave) { - smartsave = new smartSaveButton(); + smartsave = new smartSaveButton(this); connect(smartsave, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets())); connect(smartsave, SIGNAL(saveSuccessfull()), this, SLOT(clearDirty())); connect(smartsave, SIGNAL(beginOp()), this, SLOT(disableObjUpdates())); @@ -459,6 +459,12 @@ void ConfigTaskWidget::enableControls(bool enable) } } +bool ConfigTaskWidget::shouldObjectBeSaved(UAVObject *object) +{ + Q_UNUSED(object); + return true; +} + /** * SLOT function called when on of the widgets contents added to the framework changes */ diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index c4c26f0fb..191647fac 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -144,6 +144,7 @@ public: void addHelpButton(QPushButton *button, QString url); void forceShadowUpdates(); void forceConnectedState(); + virtual bool shouldObjectBeSaved(UAVObject *object); public slots: void onAutopilotDisconnect(); void onAutopilotConnect(); @@ -204,8 +205,10 @@ protected slots: virtual void refreshWidgetsValues(UAVObject *obj = NULL); virtual void updateObjectsFromWidgets(); virtual void helpButtonPressed(); + protected: virtual void enableControls(bool enable); + void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale); void updateEnableControls(); }; diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp index 20f26e7ed..0165c32bb 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp @@ -25,8 +25,9 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "smartsavebutton.h" +#include "configtaskwidget.h" -smartSaveButton::smartSaveButton() +smartSaveButton::smartSaveButton(ConfigTaskWidget *configTaskWidget) : configWidget(configTaskWidget) {} void smartSaveButton::addButtons(QPushButton *save, QPushButton *apply) @@ -77,60 +78,65 @@ void smartSaveButton::processOperation(QPushButton *button, bool save) foreach(UAVDataObject * obj, objects) { UAVObject::Metadata mdata = obj->getMetadata(); - if (UAVObject::GetGcsAccess(mdata) == UAVObject::ACCESS_READONLY) { + // Should we really save this object to the board? + if (!configWidget->shouldObjectBeSaved(obj) || UAVObject::GetGcsAccess(mdata) == UAVObject::ACCESS_READONLY) { + qDebug() << obj->getName() << "was skipped."; continue; } + up_result = false; current_object = obj; for (int i = 0; i < 3; ++i) { - qDebug() << "SMARTSAVEBUTTON" << "Upload try number" << i << "Object" << obj->getName(); + qDebug() << "Uploading" << obj->getName() << "to board."; connect(obj, SIGNAL(transactionCompleted(UAVObject *, bool)), this, SLOT(transaction_finished(UAVObject *, bool))); connect(&timer, SIGNAL(timeout()), &loop, SLOT(quit())); obj->updated(); + timer.start(3000); - // qDebug()<<"begin loop"; loop.exec(); - if (timer.isActive()) { - qDebug() << "SMARTSAVEBUTTON" << "Upload did not timeout" << i << "Object" << obj->getName(); - } else { - qDebug() << "SMARTSAVEBUTTON" << "Upload TIMEOUT" << i << "Object" << obj->getName(); + if (!timer.isActive()) { + qDebug() << "Upload of" << obj->getName() << "timed out."; } timer.stop(); + disconnect(obj, SIGNAL(transactionCompleted(UAVObject *, bool)), this, SLOT(transaction_finished(UAVObject *, bool))); disconnect(&timer, SIGNAL(timeout()), &loop, SLOT(quit())); if (up_result) { + qDebug() << "Upload of" << obj->getName() << "successful."; break; } } if (up_result == false) { - qDebug() << "SMARTSAVEBUTTON" << "Object upload error:" << obj->getName(); + qDebug() << "Upload of" << obj->getName() << "failed after 3 tries."; error = true; continue; } + sv_result = false; current_objectID = obj->getObjID(); if (save && (obj->isSettings())) { for (int i = 0; i < 3; ++i) { - qDebug() << "SMARTSAVEBUTTON" << "Save try number" << i << "Object" << obj->getName(); + qDebug() << "Saving" << obj->getName() << "to board."; connect(utilMngr, SIGNAL(saveCompleted(int, bool)), this, SLOT(saving_finished(int, bool))); connect(&timer, SIGNAL(timeout()), &loop, SLOT(quit())); utilMngr->saveObjectToSD(obj); + timer.start(3000); loop.exec(); - if (timer.isActive()) { - qDebug() << "SMARTSAVEBUTTON" << "Saving did not timeout" << i << "Object" << obj->getName(); - } else { - qDebug() << "SMARTSAVEBUTTON" << "Saving TIMEOUT" << i << "Object" << obj->getName(); + if (!timer.isActive()) { + qDebug() << "Saving of" << obj->getName() << "timed out."; } timer.stop(); + disconnect(utilMngr, SIGNAL(saveCompleted(int, bool)), this, SLOT(saving_finished(int, bool))); disconnect(&timer, SIGNAL(timeout()), &loop, SLOT(quit())); if (sv_result) { + qDebug() << "Saving of" << obj->getName() << "successful."; break; } } if (sv_result == false) { - qDebug() << "SMARTSAVEBUTTON" << "failed to save:" << obj->getName(); + qDebug() << "Saving of" << obj->getName() << "failed after 3 tries."; error = true; } } @@ -189,7 +195,6 @@ void smartSaveButton::saving_finished(int id, bool result) { if (id == current_objectID) { sv_result = result; - // qDebug()<<"saving_finished result="< #include +class ConfigTaskWidget; + class smartSaveButton : public QObject { enum buttonTypeEnum { save_button, apply_button }; public: Q_OBJECT public: - smartSaveButton(); + smartSaveButton(ConfigTaskWidget *configTaskWidget); void addButtons(QPushButton *save, QPushButton *apply); void setObjects(QList); void addObject(UAVDataObject *); @@ -79,6 +81,7 @@ private: QEventLoop loop; QList objects; QMap buttonList; + ConfigTaskWidget *configWidget; public slots: void enableControls(bool value); diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader.ui b/ground/openpilotgcs/src/plugins/uploader/uploader.ui index 253d579b3..1143f5e1f 100644 --- a/ground/openpilotgcs/src/plugins/uploader/uploader.ui +++ b/ground/openpilotgcs/src/plugins/uploader/uploader.ui @@ -6,7 +6,7 @@ 0 0 - 822 + 812 523 @@ -27,7 +27,7 @@ 0 0 - 804 + 794 505 @@ -51,55 +51,20 @@ 0 - - - - - false - - - Start a guided procedure to manually -recover a system which does not boot. - -Rescue is possible in USB mode only. - - - Auto Update - - - - - - - false - - - Tells the mainboard to go down -to bootloader mode. -(Only enabled if telemetry link is established, either -through serial or USB) - - - Halt - - - - - - - false - - - Reset the system. -(Only enabled if telemetry link is established, either -through serial or USB) - - - Reset - - - - + + + 0 + + + 0 + + + 0 + + + 6 + + true @@ -117,7 +82,33 @@ menu on the right. - + + + + true + + + <html><head/><body><p>Reboot the board and clear its settings memory.</p><p> Useful if the board cannot boot properly.</p><p> Blue led starts blinking quick for 20-30 seconds than the board will start normally</p><p><br/></p><p>If telemetry is not running, select the link using the dropdown</p><p>menu on the right.</p><p>PLEASE NOTE: Supported with bootloader versions 4.0 and earlier</p></body></html> + + + Erase settings + + + + + + + Start a guided procedure to manually +recover a system which does not boot. + +Rescue is possible in USB mode only. + + + Rescue + + + + true @@ -135,53 +126,8 @@ menu on the right. - - - - Start a guided procedure to manually -recover a system which does not boot. - -Rescue is possible in USB mode only. - - - Rescue - - - - - - - true - - - <html><head/><body><p>Reboot the board and clear its settings memory.</p><p> Useful if the board cannot boot properly.</p><p> Blue led starts blinking quick for 20-30 seconds than the board will start normally</p><p><br/></p><p>If telemetry is not running, select the link using the dropdown</p><p>menu on the right.</p><p>PLEASE NOTE: Supported with bootloader versions 4.0 and earlier</p></body></html> - - - Erase settings - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - + - - - 0 - 0 - - When telemetry is not connected, select the communication method using this combo box. @@ -192,8 +138,14 @@ halting a running board. - + + + + 0 + 23 + + Refresh the list of serial ports @@ -202,7 +154,43 @@ halting a running board. - + + + + false + + + Tells the mainboard to go down +to bootloader mode. +(Only enabled if telemetry link is established, either +through serial or USB) + + + Halt + + + + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 18 + 18 + + + + true + + + + @@ -215,26 +203,56 @@ halting a running board. - - + + + + false + + + Reset the system. +(Only enabled if telemetry link is established, either +through serial or USB) + - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 30 - 30 - - - - true + Reset + + + + false + + + + 75 + 0 + + + + Start a guided procedure to manually +recover a system which does not boot. + +Rescue is possible in USB mode only. + + + Auto Update + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp index 5fa1049ee..f90ad751c 100644 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp @@ -32,6 +32,8 @@ #define DFU_DEBUG true +const int UploaderGadgetWidget::AUTOUPDATE_CLOSE_TIMEOUT = 7000; + UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent) { m_config = new Ui_UploaderWidget(); @@ -358,16 +360,10 @@ void UploaderGadgetWidget::goToBootloader(UAVObject *callerObj, bool success) dw->populate(); m_config->systemElements->addTab(dw, QString("Device") + QString::number(i)); } - /* - m_config->haltButton->setEnabled(false); - m_config->resetButton->setEnabled(false); - */ + // Need to re-enable in case we were not connected bootButtonsSetEnable(true); - /* - m_config->telemetryLink->setEnabled(false); - m_config->rescueButton->setEnabled(false); - */ + if (resetOnly) { resetOnly = false; delay::msleep(3500); @@ -835,10 +831,14 @@ void UploaderGadgetWidget::finishAutoUpdate() { disconnect(this, SIGNAL(autoUpdateSignal(uploader::AutoUpdateStep, QVariant)), this, SLOT(autoUpdateStatus(uploader::AutoUpdateStep, QVariant))); m_config->autoUpdateOkButton->setEnabled(true); + connect(&autoUpdateCloseTimer, SIGNAL(timeout()), this, SLOT(closeAutoUpdate())); + autoUpdateCloseTimer.start(AUTOUPDATE_CLOSE_TIMEOUT); } void UploaderGadgetWidget::closeAutoUpdate() { + autoUpdateCloseTimer.stop(); + disconnect(&autoUpdateCloseTimer, SIGNAL(timeout()), this, SLOT(closeAutoUpdate())); m_config->autoUpdateGroupBox->setVisible(false); m_config->buttonFrame->setEnabled(true); m_config->splitter->setEnabled(true); diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h index 461b82daa..cf7f39586 100644 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h @@ -97,6 +97,8 @@ private: int autoUpdateConnectTimeout; FlightStatus *getFlightStatus(); void bootButtonsSetEnable(bool enabled); + static const int AUTOUPDATE_CLOSE_TIMEOUT; + QTimer autoUpdateCloseTimer; private slots: void onPhisicalHWConnect(); void versionMatchCheck(); diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index 99c89e5bb..ebf5aa7f6 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -48,27 +48,27 @@ limits="\ %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ - %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ + %0903NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ \ %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ - %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ + %0903NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ \ %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ - %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ + %0903NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ \ %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ - %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ + %0903NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ \ %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ - %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ + %0903NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI;\ \ %0401NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ %0402NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI,\ - %0903NE:Autotune:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI"/> + %0903NE:Autotune:AltitudeVario:AltitudeHold:VelocityControl:PositionHold:ReturnToBase:Land:PathPlanner:POI"/>