From 246318af7b5333e0149d40dfa80e0a28ee75e433 Mon Sep 17 00:00:00 2001 From: zedamota Date: Tue, 20 Sep 2011 22:14:48 +0100 Subject: [PATCH 01/18] Mixer bug fix try --- .../plugins/config/configairframewidget.cpp | 10 +++++++++ .../src/plugins/config/configtaskwidget.cpp | 22 +++++++++++++++++++ .../src/plugins/config/configtaskwidget.h | 3 +++ 3 files changed, 35 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp b/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp index a12d34dca..6a6ad66be 100644 --- a/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp @@ -36,6 +36,9 @@ #include #include #include +#include "systemsettings.h" +#include "mixersettings.h" +#include "actuatorsettings.h" /** Helper delegate for the custom mixer editor table. @@ -443,6 +446,13 @@ void ConfigAirframeWidget::updateCustomThrottle2CurveValue(QList list, d */ void ConfigAirframeWidget::refreshWidgetsValues() { + if(!allObjectsUpdated()) + { + SystemSettings::GetInstance(getObjectManager())->requestUpdate(); + MixerSettings::GetInstance(getObjectManager())->requestUpdate(); + ActuatorSettings::GetInstance(getObjectManager())->requestUpdate(); + return; + } bool dirty=isDirty(); // Get the Airframe type from the system settings: UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("SystemSettings"))); diff --git a/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp index 98b10683c..cad342d6f 100644 --- a/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp @@ -62,6 +62,8 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel { obj = objManager->getObject(QString(object)); Q_ASSERT(obj); + objectUpdates.insert(obj,false); + connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*))); connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues())); } //smartsave->addObject(obj); @@ -153,6 +155,10 @@ void ConfigTaskWidget::onAutopilotDisconnect() { isConnected=false; enableControls(false); + foreach(UAVObject *obj, objectUpdates.keys()) + { + objectUpdates[obj]=false; + } } void ConfigTaskWidget::onAutopilotConnect() @@ -308,6 +314,22 @@ void ConfigTaskWidget::enableObjUpdates() } } +void ConfigTaskWidget::objectUpdated(UAVObject *obj) +{ + objectUpdates[obj]=true; +} + +bool ConfigTaskWidget::allObjectsUpdated() +{ + bool ret=true; + foreach(UAVObject *obj, objectUpdates.keys()) + { + ret=ret & objectUpdates[obj]; + } + qDebug()<<"ALL OBJECTS UPDATE:"< objectUpdates; bool dirty; protected slots: virtual void disableObjUpdates(); From 352620e0ed4fb8bb86069541cb4e69e1656b2525 Mon Sep 17 00:00:00 2001 From: zedamota Date: Fri, 23 Sep 2011 13:48:27 +0100 Subject: [PATCH 02/18] Mixer bug while import fix (try to) --- .../src/plugins/config/Config.pluginspec | 1 + .../src/plugins/config/config.pro | 2 +- .../src/plugins/config/configtaskwidget.cpp | 58 +-- .../src/plugins/config/configtaskwidget.h | 7 +- ground/openpilotgcs/src/plugins/plugins.pro | 1 + .../uavsettingsimportexport.cpp | 321 +--------------- .../uavsettingsimportexport.h | 15 +- .../uavsettingsimportexport.pri | 2 + .../uavsettingsimportexport.pro | 8 +- .../uavsettingsimportexport_global.h | 40 ++ .../uavsettingsimportexportfactory.cpp | 363 ++++++++++++++++++ .../uavsettingsimportexportfactory.h | 54 +++ 12 files changed, 519 insertions(+), 353 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pri create mode 100644 ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport_global.h create mode 100644 ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp create mode 100644 ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h diff --git a/ground/openpilotgcs/src/plugins/config/Config.pluginspec b/ground/openpilotgcs/src/plugins/config/Config.pluginspec index 0a9da6e94..83013fd28 100644 --- a/ground/openpilotgcs/src/plugins/config/Config.pluginspec +++ b/ground/openpilotgcs/src/plugins/config/Config.pluginspec @@ -9,5 +9,6 @@ + diff --git a/ground/openpilotgcs/src/plugins/config/config.pro b/ground/openpilotgcs/src/plugins/config/config.pro index 29d872ec9..b99fc9edc 100644 --- a/ground/openpilotgcs/src/plugins/config/config.pro +++ b/ground/openpilotgcs/src/plugins/config/config.pro @@ -8,7 +8,7 @@ include(../../plugins/uavtalk/uavtalk.pri) include(../../plugins/coreplugin/coreplugin.pri) include(../../plugins/uavobjects/uavobjects.pri) include(../../plugins/uavobjectutil/uavobjectutil.pri) - +include(../../plugins/uavsettingsimportexport/uavsettingsimportexport.pri) INCLUDEPATH += ../../libs/eigen OTHER_FILES += Config.pluginspec diff --git a/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp index cad342d6f..f40225e71 100644 --- a/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp @@ -26,14 +26,17 @@ */ #include "configtaskwidget.h" #include - +#include "uavsettingsimportexport/uavsettingsimportexportfactory.h" +#include "configgadgetwidget.h" ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false) { pm = ExtensionSystem::PluginManager::instance(); objManager = pm->getObject(); - connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); - connect(parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect())); + connect((ConfigGadgetWidget*)parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); + connect((ConfigGadgetWidget*)parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect())); + UAVSettingsImportExportFactory * importexportplugin = pm->getObject(); + connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(invalidateObjects())); } void ConfigTaskWidget::addWidget(QWidget * widget) { @@ -62,8 +65,8 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel { obj = objManager->getObject(QString(object)); Q_ASSERT(obj); - objectUpdates.insert(obj,false); - connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*))); + objectUpdates.insert(obj,false); + connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*))); connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues())); } //smartsave->addObject(obj); @@ -155,10 +158,7 @@ void ConfigTaskWidget::onAutopilotDisconnect() { isConnected=false; enableControls(false); - foreach(UAVObject *obj, objectUpdates.keys()) - { - objectUpdates[obj]=false; - } + invalidateObjects(); } void ConfigTaskWidget::onAutopilotConnect() @@ -314,22 +314,30 @@ void ConfigTaskWidget::enableObjUpdates() } } -void ConfigTaskWidget::objectUpdated(UAVObject *obj) -{ - objectUpdates[obj]=true; -} - -bool ConfigTaskWidget::allObjectsUpdated() -{ - bool ret=true; - foreach(UAVObject *obj, objectUpdates.keys()) - { - ret=ret & objectUpdates[obj]; - } - qDebug()<<"ALL OBJECTS UPDATE:"< objectUpdates; + QMap objectUpdates; bool dirty; protected slots: virtual void disableObjUpdates(); diff --git a/ground/openpilotgcs/src/plugins/plugins.pro b/ground/openpilotgcs/src/plugins/plugins.pro index 7a86f53be..12e7d7c43 100644 --- a/ground/openpilotgcs/src/plugins/plugins.pro +++ b/ground/openpilotgcs/src/plugins/plugins.pro @@ -107,6 +107,7 @@ SUBDIRS += plugin_systemhealth plugin_config.subdir = config plugin_config.depends = plugin_coreplugin plugin_config.depends += plugin_uavobjects +plugin_config.depends += plugin_uavsettingsimportexport SUBDIRS += plugin_config #GPS Display gadget diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.cpp b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.cpp index 342b845e9..5418b455c 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.cpp +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.cpp @@ -31,7 +31,7 @@ #include #include #include - +#include "importsummary.h" // for menu item #include #include @@ -62,321 +62,20 @@ UAVSettingsImportExportPlugin::~UAVSettingsImportExportPlugin() bool UAVSettingsImportExportPlugin::initialize(const QStringList& args, QString *errMsg) { - Q_UNUSED(args); - Q_UNUSED(errMsg); - - // Add Menu entry - Core::ActionManager* am = Core::ICore::instance()->actionManager(); - Core::ActionContainer* ac = am->actionContainer(Core::Constants::M_FILE); - Core::Command* cmd = am->registerAction(new QAction(this), - "UAVSettingsImportExportPlugin.UAVSettingsExport", - QList() << - Core::Constants::C_GLOBAL_ID); - cmd->setDefaultKeySequence(QKeySequence("Ctrl+E")); - cmd->action()->setText(tr("Export UAV Settings...")); - ac->addAction(cmd, Core::Constants::G_FILE_SAVE); - connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVSettings())); - - cmd = am->registerAction(new QAction(this), - "UAVSettingsImportExportPlugin.UAVSettingsImport", - QList() << - Core::Constants::C_GLOBAL_ID); - cmd->setDefaultKeySequence(QKeySequence("Ctrl+I")); - cmd->action()->setText(tr("Import UAV Settings...")); - ac->addAction(cmd, Core::Constants::G_FILE_SAVE); - connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(importUAVSettings())); - - cmd = am->registerAction(new QAction(this), - "UAVSettingsImportExportPlugin.UAVDataExport", - QList() << - Core::Constants::C_GLOBAL_ID); - cmd->action()->setText(tr("Export UAV Data...")); - ac->addAction(cmd, Core::Constants::G_FILE_SAVE); - connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVData())); - + Q_UNUSED(args); + Q_UNUSED(errMsg); + mf = new UAVSettingsImportExportFactory(this); + addAutoReleasedObject(mf); return true; -} - -void UAVSettingsImportExportPlugin::extensionsInitialized() -{ - // Do nothing -} - - -// Slot called by the menu manager on user action -void UAVSettingsImportExportPlugin::importUAVSettings() -{ - // ask for file name - QString fileName; - QString filters = tr("UAVSettings XML files (*.uav);; XML files (*.xml)"); - fileName = QFileDialog::getOpenFileName(0, tr("Import UAV Settings"), "", filters); - if (fileName.isEmpty()) { - return; - } - - // Now open the file - QFile file(fileName); - QDomDocument doc("UAVSettings"); - file.open(QFile::ReadOnly|QFile::Text); - if (!doc.setContent(file.readAll())) { - QMessageBox msgBox; - msgBox.setText(tr("File Parsing Failed.")); - msgBox.setInformativeText(tr("This file is not a correct XML file")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.exec(); - return; - } - file.close(); - - QDomElement root = doc.documentElement(); - if (root.tagName() != "settings") { - QMessageBox msgBox; - msgBox.setText(tr("Wrong file contents.")); - msgBox.setInformativeText(tr("This file is not a correct UAVSettings file")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.exec(); - return; - } - - // We are now ok: setup the import summary dialog & update it as we - // go along. - ImportSummaryDialog swui; - - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - swui.show(); - - QDomNode node = root.firstChild(); - while (!node.isNull()) { - QDomElement e = node.toElement(); - if (e.tagName() == "object") { - // - Read each object - QString uavObjectName = e.attribute("name"); - uint uavObjectID = e.attribute("id").toUInt(NULL,16); - - // Sanity Check: - UAVObject* obj = objManager->getObject(uavObjectName); - if (obj == NULL) { - // This object is unknown! - qDebug() << "Object unknown:" << uavObjectName << uavObjectID; - swui.addLine(uavObjectName, "Error (Object unknown)", false); - - } else { - // - Update each field - // - Issue and "updated" command - bool error=false; - QDomNode field = node.firstChild(); - while(!field.isNull()) { - QDomElement f = field.toElement(); - if (f.tagName() == "field") { - UAVObjectField *uavfield = obj->getField(f.attribute("name")); - if (uavfield) { - QStringList list = f.attribute("values").split(","); - if (list.length() == 1) { - uavfield->setValue(f.attribute("values")); - } else { - // This is an enum: - int i=0; - QStringList list = f.attribute("values").split(","); - foreach (QString element, list) { - uavfield->setValue(element,i++); - } - } - error = false; - } else { - error = true; - } - } - field = field.nextSibling(); - } - obj->updated(); - if (error) { - swui.addLine(uavObjectName, "Warning (Object field unknown)", true); - } else if (uavObjectID != obj->getObjID()) { - qDebug() << "Mismatch for Object " << uavObjectName << uavObjectID << " - " << obj->getObjID(); - swui.addLine(uavObjectName, "Warning (ObjectID mismatch)", true); - } else - swui.addLine(uavObjectName, "OK", true); - } - } - node = node.nextSibling(); - } - swui.exec(); - - - -} - -// Create an XML document from UAVObject database -QString UAVSettingsImportExportPlugin::createXMLDocument( - const QString docName, const bool isSettings, const bool fullExport) -{ - // generate an XML first (used for all export formats as a formatted data source) - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - - QDomDocument doc(docName); - QDomElement root = doc.createElement(isSettings ? "settings" : "data"); - doc.appendChild(root); - QDomElement versionInfo =doc.createElement("versionInfo"); - root.appendChild(versionInfo); - QDomElement fw=doc.createElement("Embedded"); - UAVObjectUtilManager* utilMngr = pm->getObject(); - - fw.setAttribute("gitcommittag",utilMngr->getBoardDescriptionStruct().gitTag); - fw.setAttribute("fwtag",utilMngr->getBoardDescriptionStruct().description); - fw.setAttribute("cpuSerial",QString(utilMngr->getBoardCPUSerial().toHex())); - - versionInfo.appendChild(fw); - QDomElement gcs=doc.createElement("GCS"); - gcs.setAttribute("revision",QString::fromLatin1(Core::Constants::GCS_REVISION_STR)); - versionInfo.appendChild(gcs); - // iterate over settings objects - QList< QList > objList = objManager->getDataObjects(); - foreach (QList list, objList) { - foreach (UAVDataObject* obj, list) { - if (obj->isSettings() == isSettings) { - - // add each object to the XML - QDomElement o = doc.createElement("object"); - o.setAttribute("name", obj->getName()); - o.setAttribute("id", QString("0x")+ QString().setNum(obj->getObjID(),16).toUpper()); - if (fullExport) { - QDomElement d = doc.createElement("description"); - QDomText t = doc.createTextNode(obj->getDescription().remove("@Ref ", Qt::CaseInsensitive)); - d.appendChild(t); - o.appendChild(d); - } - - // iterate over fields - QList fieldList = obj->getFields(); - - foreach (UAVObjectField* field, fieldList) { - QDomElement f = doc.createElement("field"); - - // iterate over values - QString vals; - quint32 nelem = field->getNumElements(); - for (unsigned int n = 0; n < nelem; ++n) { - vals.append(QString("%1,").arg(field->getValue(n).toString())); - } - vals.chop(1); - - f.setAttribute("name", field->getName()); - f.setAttribute("values", vals); - if (fullExport) { - f.setAttribute("type", field->getTypeAsString()); - f.setAttribute("units", field->getUnits()); - f.setAttribute("elements", nelem); - if (field->getType() == UAVObjectField::ENUM) { - f.setAttribute("options", field->getOptions().join(",")); - } - } - o.appendChild(f); - } - root.appendChild(o); - } - } - } - - return doc.toString(4); -} - -// Slot called by the menu manager on user action -void UAVSettingsImportExportPlugin::exportUAVSettings() -{ - // ask for file name - QString fileName; - QString filters = tr("UAVSettings XML files (*.uav)"); - - fileName = QFileDialog::getSaveFileName(0, tr("Save UAV Settings File As"), "", filters); - if (fileName.isEmpty()) { - return; - } - - bool fullExport = false; - // If the filename ends with .xml, we will do a full export, otherwise, a simple export - if (fileName.endsWith(".xml")) { - fullExport = true; - } else if (!fileName.endsWith(".uav")) { - fileName.append(".uav"); - } - - // generate an XML first (used for all export formats as a formatted data source) - QString xml = createXMLDocument("UAVSettings", true, fullExport); - - // save file - QFile file(fileName); - if (file.open(QIODevice::WriteOnly) && - (file.write(xml.toAscii()) != -1)) { - file.close(); - } else { - QMessageBox::critical(0, - tr("UAV Settings Export"), - tr("Unable to save settings: ") + fileName, - QMessageBox::Ok); - return; - } - - QMessageBox msgBox; - msgBox.setText(tr("Settings saved.")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.exec(); -} - -// Slot called by the menu manager on user action -void UAVSettingsImportExportPlugin::exportUAVData() -{ - if (QMessageBox::question(0, tr("Are you sure?"), - tr("This option is only useful for passing your current " - "system data to the technical support staff. " - "Do you really want to export?"), - QMessageBox::Ok | QMessageBox::Cancel, - QMessageBox::Ok) != QMessageBox::Ok) { - return; - } - - // ask for file name - QString fileName; - QString filters = tr("UAVData XML files (*.uav)"); - - fileName = QFileDialog::getSaveFileName(0, tr("Save UAV Data File As"), "", filters); - if (fileName.isEmpty()) { - return; - } - - bool fullExport = false; - // If the filename ends with .xml, we will do a full export, otherwise, a simple export - if (fileName.endsWith(".xml")) { - fullExport = true; - } else if (!fileName.endsWith(".uav")) { - fileName.append(".uav"); - } - - // generate an XML first (used for all export formats as a formatted data source) - QString xml = createXMLDocument("UAVData", false, fullExport); - - // save file - QFile file(fileName); - if (file.open(QIODevice::WriteOnly) && - (file.write(xml.toAscii()) != -1)) { - file.close(); - } else { - QMessageBox::critical(0, - tr("UAV Data Export"), - tr("Unable to save data: ") + fileName, - QMessageBox::Ok); - return; - } - - QMessageBox msgBox; - msgBox.setText(tr("Data saved.")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.exec(); } void UAVSettingsImportExportPlugin::shutdown() { // Do nothing } +void UAVSettingsImportExportPlugin::extensionsInitialized() +{ +} Q_EXPORT_PLUGIN(UAVSettingsImportExportPlugin) + + diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.h b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.h index ff8972227..a63454153 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.h +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.h @@ -29,9 +29,10 @@ #include #include "uavobjectutil/uavobjectutilmanager.h" -#include "importsummary.h" +#include "uavsettingsimportexport_global.h" #include "../../../../../build/ground/openpilotgcs/gcsversioninfo.h" -class UAVSettingsImportExportPlugin : public ExtensionSystem::IPlugin +#include "uavsettingsimportexportfactory.h" +class UAVSETTINGSIMPORTEXPORT_EXPORT UAVSettingsImportExportPlugin : public ExtensionSystem::IPlugin { Q_OBJECT @@ -42,16 +43,10 @@ public: void extensionsInitialized(); bool initialize(const QStringList & arguments, QString * errorString); void shutdown(); - private: - QString createXMLDocument(const QString docName, - const bool isSettings, - const bool fullExport); + UAVSettingsImportExportFactory *mf; + -private slots: - void importUAVSettings(); - void exportUAVSettings(); - void exportUAVData(); }; diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pri b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pri new file mode 100644 index 000000000..bddd38181 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pri @@ -0,0 +1,2 @@ +include(uavsettingsimportexport_dependencies.pri) +LIBS *= -l$$qtLibraryName(UAVSettingsImportExport) diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pro b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pro index fcdc11ae6..aa8abccf1 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pro +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pro @@ -3,14 +3,16 @@ TEMPLATE = lib QT += xml TARGET = UAVSettingsImportExport - +DEFINES += UAVSETTINGSIMPORTEXPORT_LIBRARY include(../../openpilotgcsplugin.pri) include(uavsettingsimportexport_dependencies.pri) HEADERS += uavsettingsimportexport.h \ - importsummary.h + importsummary.h \ + uavsettingsimportexportfactory.h SOURCES += uavsettingsimportexport.cpp \ - importsummary.cpp + importsummary.cpp \ + uavsettingsimportexportfactory.cpp OTHER_FILES += uavsettingsimportexport.pluginspec diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport_global.h b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport_global.h new file mode 100644 index 000000000..703771b4f --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport_global.h @@ -0,0 +1,40 @@ +/** + ****************************************************************************** + * + * @file uavsettingsimportexport_global.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @see The GNU Public License (GPL) Version 3 + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup + * @{ + * @brief + *****************************************************************************/ +/* + * 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 + */ + +#ifndef UAVSETTINGSIMPORTEXPORT_GLOBAL_H +#define UAVSETTINGSIMPORTEXPORT_GLOBAL_H + +#include + +#if defined(UAVSETTINGSIMPORTEXPORT_LIBRARY) +# define UAVSETTINGSIMPORTEXPORT_EXPORT Q_DECL_EXPORT +#else +# define UAVSETTINGSIMPORTEXPORT_EXPORT Q_DECL_IMPORT +#endif + +#endif // UAVSETTINGSIMPORTEXPORT_GLOBAL_H diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp new file mode 100644 index 000000000..be81222fe --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp @@ -0,0 +1,363 @@ +/** + ****************************************************************************** + * + * @file uavsettingsimportexportfactory.cpp + * @author (C) 2011 The OpenPilot Team, http://www.openpilot.org + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup UAVSettingsImportExport UAVSettings Import/Export Plugin + * @{ + * @brief UAVSettings Import/Export Plugin + *****************************************************************************/ +/* + * 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 "uavsettingsimportexportfactory.h" +#include +#include +#include +#include +#include "importsummary.h" +// for menu item +#include +#include +#include +#include + +// for UAVObjects +#include "uavdataobject.h" +#include "uavobjectmanager.h" +#include "extensionsystem/pluginmanager.h" + +// for XML object +#include + +// for file dialog and error messages +#include +#include + + + +UAVSettingsImportExportFactory::~UAVSettingsImportExportFactory() +{ + // Do nothing +} + +UAVSettingsImportExportFactory::UAVSettingsImportExportFactory(QObject * parent):QObject(parent) +{ + + // Add Menu entry + Core::ActionManager* am = Core::ICore::instance()->actionManager(); + Core::ActionContainer* ac = am->actionContainer(Core::Constants::M_FILE); + Core::Command* cmd = am->registerAction(new QAction(this), + "UAVSettingsImportExportPlugin.UAVSettingsExport", + QList() << + Core::Constants::C_GLOBAL_ID); + cmd->setDefaultKeySequence(QKeySequence("Ctrl+E")); + cmd->action()->setText(tr("Export UAV Settings...")); + ac->addAction(cmd, Core::Constants::G_FILE_SAVE); + connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVSettings())); + + cmd = am->registerAction(new QAction(this), + "UAVSettingsImportExportPlugin.UAVSettingsImport", + QList() << + Core::Constants::C_GLOBAL_ID); + cmd->setDefaultKeySequence(QKeySequence("Ctrl+I")); + cmd->action()->setText(tr("Import UAV Settings...")); + ac->addAction(cmd, Core::Constants::G_FILE_SAVE); + connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(importUAVSettings())); + + cmd = am->registerAction(new QAction(this), + "UAVSettingsImportExportPlugin.UAVDataExport", + QList() << + Core::Constants::C_GLOBAL_ID); + cmd->action()->setText(tr("Export UAV Data...")); + ac->addAction(cmd, Core::Constants::G_FILE_SAVE); + connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVData())); + +} + +// Slot called by the menu manager on user action +void UAVSettingsImportExportFactory::importUAVSettings() +{ + // ask for file name + QString fileName; + QString filters = tr("UAVSettings XML files (*.uav);; XML files (*.xml)"); + fileName = QFileDialog::getOpenFileName(0, tr("Import UAV Settings"), "", filters); + if (fileName.isEmpty()) { + return; + } + + // Now open the file + QFile file(fileName); + QDomDocument doc("UAVSettings"); + file.open(QFile::ReadOnly|QFile::Text); + if (!doc.setContent(file.readAll())) { + QMessageBox msgBox; + msgBox.setText(tr("File Parsing Failed.")); + msgBox.setInformativeText(tr("This file is not a correct XML file")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.exec(); + return; + } + file.close(); + emit importAboutToBegin(); + QDomElement root = doc.documentElement(); + if (root.tagName() != "settings") { + QMessageBox msgBox; + msgBox.setText(tr("Wrong file contents.")); + msgBox.setInformativeText(tr("This file is not a correct UAVSettings file")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.exec(); + return; + } + + // We are now ok: setup the import summary dialog & update it as we + // go along. + ImportSummaryDialog swui; + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *objManager = pm->getObject(); + swui.show(); + + QDomNode node = root.firstChild(); + while (!node.isNull()) { + QDomElement e = node.toElement(); + if (e.tagName() == "object") { + // - Read each object + QString uavObjectName = e.attribute("name"); + uint uavObjectID = e.attribute("id").toUInt(NULL,16); + + // Sanity Check: + UAVObject* obj = objManager->getObject(uavObjectName); + if (obj == NULL) { + // This object is unknown! + qDebug() << "Object unknown:" << uavObjectName << uavObjectID; + swui.addLine(uavObjectName, "Error (Object unknown)", false); + + } else { + // - Update each field + // - Issue and "updated" command + bool error=false; + QDomNode field = node.firstChild(); + while(!field.isNull()) { + QDomElement f = field.toElement(); + if (f.tagName() == "field") { + UAVObjectField *uavfield = obj->getField(f.attribute("name")); + if (uavfield) { + QStringList list = f.attribute("values").split(","); + if (list.length() == 1) { + uavfield->setValue(f.attribute("values")); + } else { + // This is an enum: + int i=0; + QStringList list = f.attribute("values").split(","); + foreach (QString element, list) { + uavfield->setValue(element,i++); + } + } + error = false; + } else { + error = true; + } + } + field = field.nextSibling(); + } + obj->updated(); + if (error) { + swui.addLine(uavObjectName, "Warning (Object field unknown)", true); + } else if (uavObjectID != obj->getObjID()) { + qDebug() << "Mismatch for Object " << uavObjectName << uavObjectID << " - " << obj->getObjID(); + swui.addLine(uavObjectName, "Warning (ObjectID mismatch)", true); + } else + swui.addLine(uavObjectName, "OK", true); + } + } + node = node.nextSibling(); + } + swui.exec(); + + + +} + +// Create an XML document from UAVObject database +QString UAVSettingsImportExportFactory::createXMLDocument( + const QString docName, const bool isSettings, const bool fullExport) +{ + // generate an XML first (used for all export formats as a formatted data source) + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *objManager = pm->getObject(); + + QDomDocument doc(docName); + QDomElement root = doc.createElement(isSettings ? "settings" : "data"); + doc.appendChild(root); + QDomElement versionInfo =doc.createElement("versionInfo"); + root.appendChild(versionInfo); + QDomElement fw=doc.createElement("Embedded"); + UAVObjectUtilManager* utilMngr = pm->getObject(); + + fw.setAttribute("gitcommittag",utilMngr->getBoardDescriptionStruct().gitTag); + fw.setAttribute("fwtag",utilMngr->getBoardDescriptionStruct().description); + fw.setAttribute("cpuSerial",QString(utilMngr->getBoardCPUSerial().toHex())); + + versionInfo.appendChild(fw); + QDomElement gcs=doc.createElement("GCS"); + gcs.setAttribute("revision",QString::fromLatin1(Core::Constants::GCS_REVISION_STR)); + versionInfo.appendChild(gcs); + // iterate over settings objects + QList< QList > objList = objManager->getDataObjects(); + foreach (QList list, objList) { + foreach (UAVDataObject* obj, list) { + if (obj->isSettings() == isSettings) { + + // add each object to the XML + QDomElement o = doc.createElement("object"); + o.setAttribute("name", obj->getName()); + o.setAttribute("id", QString("0x")+ QString().setNum(obj->getObjID(),16).toUpper()); + if (fullExport) { + QDomElement d = doc.createElement("description"); + QDomText t = doc.createTextNode(obj->getDescription().remove("@Ref ", Qt::CaseInsensitive)); + d.appendChild(t); + o.appendChild(d); + } + + // iterate over fields + QList fieldList = obj->getFields(); + + foreach (UAVObjectField* field, fieldList) { + QDomElement f = doc.createElement("field"); + + // iterate over values + QString vals; + quint32 nelem = field->getNumElements(); + for (unsigned int n = 0; n < nelem; ++n) { + vals.append(QString("%1,").arg(field->getValue(n).toString())); + } + vals.chop(1); + + f.setAttribute("name", field->getName()); + f.setAttribute("values", vals); + if (fullExport) { + f.setAttribute("type", field->getTypeAsString()); + f.setAttribute("units", field->getUnits()); + f.setAttribute("elements", nelem); + if (field->getType() == UAVObjectField::ENUM) { + f.setAttribute("options", field->getOptions().join(",")); + } + } + o.appendChild(f); + } + root.appendChild(o); + } + } + } + + return doc.toString(4); +} + +// Slot called by the menu manager on user action +void UAVSettingsImportExportFactory::exportUAVSettings() +{ + // ask for file name + QString fileName; + QString filters = tr("UAVSettings XML files (*.uav)"); + + fileName = QFileDialog::getSaveFileName(0, tr("Save UAV Settings File As"), "", filters); + if (fileName.isEmpty()) { + return; + } + + bool fullExport = false; + // If the filename ends with .xml, we will do a full export, otherwise, a simple export + if (fileName.endsWith(".xml")) { + fullExport = true; + } else if (!fileName.endsWith(".uav")) { + fileName.append(".uav"); + } + + // generate an XML first (used for all export formats as a formatted data source) + QString xml = createXMLDocument("UAVSettings", true, fullExport); + + // save file + QFile file(fileName); + if (file.open(QIODevice::WriteOnly) && + (file.write(xml.toAscii()) != -1)) { + file.close(); + } else { + QMessageBox::critical(0, + tr("UAV Settings Export"), + tr("Unable to save settings: ") + fileName, + QMessageBox::Ok); + return; + } + + QMessageBox msgBox; + msgBox.setText(tr("Settings saved.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.exec(); +} + +// Slot called by the menu manager on user action +void UAVSettingsImportExportFactory::exportUAVData() +{ + if (QMessageBox::question(0, tr("Are you sure?"), + tr("This option is only useful for passing your current " + "system data to the technical support staff. " + "Do you really want to export?"), + QMessageBox::Ok | QMessageBox::Cancel, + QMessageBox::Ok) != QMessageBox::Ok) { + return; + } + + // ask for file name + QString fileName; + QString filters = tr("UAVData XML files (*.uav)"); + + fileName = QFileDialog::getSaveFileName(0, tr("Save UAV Data File As"), "", filters); + if (fileName.isEmpty()) { + return; + } + + bool fullExport = false; + // If the filename ends with .xml, we will do a full export, otherwise, a simple export + if (fileName.endsWith(".xml")) { + fullExport = true; + } else if (!fileName.endsWith(".uav")) { + fileName.append(".uav"); + } + + // generate an XML first (used for all export formats as a formatted data source) + QString xml = createXMLDocument("UAVData", false, fullExport); + + // save file + QFile file(fileName); + if (file.open(QIODevice::WriteOnly) && + (file.write(xml.toAscii()) != -1)) { + file.close(); + } else { + QMessageBox::critical(0, + tr("UAV Data Export"), + tr("Unable to save data: ") + fileName, + QMessageBox::Ok); + return; + } + + QMessageBox msgBox; + msgBox.setText(tr("Data saved.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.exec(); +} diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h new file mode 100644 index 000000000..2ef5f803e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h @@ -0,0 +1,54 @@ +/** + ****************************************************************************** + * + * @file uavsettingsimportexportfactory.h + * @author (C) 2011 The OpenPilot Team, http://www.openpilot.org + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup UAVSettingsImportExport UAVSettings Import/Export Plugin + * @{ + * @brief UAVSettings Import/Export Plugin + *****************************************************************************/ +/* + * 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 + */ +#ifndef UAVSETTINGSIMPORTEXPORTFACTORY_H +#define UAVSETTINGSIMPORTEXPORTFACTORY_H +#include "uavsettingsimportexport_global.h" +#include "uavobjectutil/uavobjectutilmanager.h" +#include "../../../../../build/ground/openpilotgcs/gcsversioninfo.h" +class UAVSETTINGSIMPORTEXPORT_EXPORT UAVSettingsImportExportFactory : public QObject +{ + Q_OBJECT + +public: + UAVSettingsImportExportFactory(QObject *parent = 0); + ~UAVSettingsImportExportFactory(); + +private: + QString createXMLDocument(const QString docName, + const bool isSettings, + const bool fullExport); + +private slots: + void importUAVSettings(); + void exportUAVSettings(); + void exportUAVData(); +signals: + void importAboutToBegin(); + +}; + +#endif // UAVSETTINGSIMPORTEXPORTFACTORY_H From 822cbfbc8171d0ad4d62dc6bc2f3e4a2203c596b Mon Sep 17 00:00:00 2001 From: Edouard Lafargue Date: Sun, 25 Sep 2011 15:26:12 +0200 Subject: [PATCH 03/18] Fix MacOS halt issues by using the USBMonitor to detect device re-insertion:wq: --- .../src/plugins/rawhid/usbmonitor_mac.cpp | 5 ++- .../src/plugins/uploader/op_dfu.cpp | 37 +++++++++---------- .../src/plugins/uploader/op_dfu.h | 1 + .../plugins/uploader/uploadergadgetwidget.cpp | 4 +- 4 files changed, 23 insertions(+), 24 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp index e094a9a68..51fd6cce7 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp +++ b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp @@ -117,7 +117,7 @@ void USBMonitor::removeDevice(IOHIDDeviceRef dev) { */ void USBMonitor::detach_callback(void *context, IOReturn r, void *hid_mgr, IOHIDDeviceRef dev) { - + qDebug() << "USBMonitor: Device detached event"; instance()->removeDevice(dev); } @@ -136,6 +136,8 @@ void USBMonitor::attach_callback(void *context, IOReturn r, void *hid_mgr, IOHID deviceInfo.dev_handle = dev; + qDebug() << "USBMonitor: Device attached event"; + // Populate the device info structure got_properties &= HID_GetIntProperty(dev, CFSTR( kIOHIDVendorIDKey ), &deviceInfo.vendorID); got_properties &= HID_GetIntProperty(dev, CFSTR( kIOHIDProductIDKey ), &deviceInfo.productID); @@ -149,6 +151,7 @@ void USBMonitor::attach_callback(void *context, IOReturn r, void *hid_mgr, IOHID // Currently only enumerating objects that have the complete list of properties if(got_properties) { + qDebug() << "USBMonitor: Adding device"; instance()->addDevice(deviceInfo); } } diff --git a/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp b/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp index 8a9045233..edd5dfb0b 100644 --- a/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp @@ -80,29 +80,26 @@ DFUObject::DFUObject(bool _debug,bool _use_serial,QString portname): } else { - send_delay=10; - use_delay=true; -// int numDevices=0; QList devices; - int count=0; - while((devices.length()==0) && count < 10) - { - if (debug) - qDebug() << "."; - delay::msleep(500); - // processEvents enables XP to process the system - // plug/unplug events, otherwise it will not process - // those events before the end of the call! - QApplication::processEvents(); - devices = USBMonitor::instance()->availableDevices(0x20a0,-1,-1,USBMonitor::Bootloader); - count++; - } - if (devices.length()==1) { + devices = USBMonitor::instance()->availableDevices(0x20a0,-1,-1,USBMonitor::Bootloader); + if (devices.length()==1) { hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0); } else { - qDebug() << devices.length() << " device(s) detected, don't know what to do!"; - mready = false; - } + // Wait for the board to appear on the USB bus: + QEventLoop m_eventloop; + connect(USBMonitor::instance(), SIGNAL(deviceDiscovered(USBPortInfo)),&m_eventloop, SLOT(quit())); + QTimer::singleShot(5000,&m_eventloop, SLOT(quit())); + m_eventloop.exec(); + devices = USBMonitor::instance()->availableDevices(0x20a0,-1,-1,USBMonitor::Bootloader); + if (devices.length()==1) { + delay::msleep(2000); // Let the USB Subsystem settle (especially important on Mac!) + hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0); + } + else { + qDebug() << devices.length() << " device(s) detected, don't know what to do!"; + mready = false; + } + } } } diff --git a/ground/openpilotgcs/src/plugins/uploader/op_dfu.h b/ground/openpilotgcs/src/plugins/uploader/op_dfu.h index 420e0a3ea..1fc92637c 100644 --- a/ground/openpilotgcs/src/plugins/uploader/op_dfu.h +++ b/ground/openpilotgcs/src/plugins/uploader/op_dfu.h @@ -17,6 +17,7 @@ #include "delay.h" #include #include +#include #include "SSP/qssp.h" #include "SSP/port.h" #include "SSP/qsspt.h" diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp index 397533c2b..883955a5b 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp @@ -235,9 +235,7 @@ void UploaderGadgetWidget::goToBootloader(UAVObject* callerObj, bool success) currentStep = IAP_STATE_BOOTLOADER; // Tell the mainboard to get into bootloader state: - log("Detecting devices, please wait 5 seconds..."); - this->repaint(); - delay::msleep(5100); // Required to let the board(s) settle + log("Detecting devices, please wait a few seconds..."); if (!dfu) { if (dlj.startsWith("USB")) dfu = new DFUObject(DFU_DEBUG, false, QString()); From 797bb38081fc7def804d2398bb213f0277d7c9da Mon Sep 17 00:00:00 2001 From: zedamota Date: Sun, 25 Sep 2011 19:30:32 +0100 Subject: [PATCH 04/18] mixer bug fix. Also added a new debug plugin witch shows the debug messages normally not available on release builds --- .../plugins/config/configairframewidget.cpp | 6 +- .../src/plugins/config/configtaskwidget.cpp | 3 +- .../debuggadget/DebugGadget.pluginspec | 10 ++ .../src/plugins/debuggadget/debug.ui | 31 ++++++ .../src/plugins/debuggadget/debugengine.cpp | 13 +++ .../src/plugins/debuggadget/debugengine.h | 18 ++++ .../src/plugins/debuggadget/debuggadget.cpp | 39 ++++++++ .../src/plugins/debuggadget/debuggadget.h | 59 ++++++++++++ .../src/plugins/debuggadget/debuggadget.pro | 21 ++++ .../debuggadget/debuggadgetfactory.cpp | 47 +++++++++ .../plugins/debuggadget/debuggadgetfactory.h | 50 ++++++++++ .../plugins/debuggadget/debuggadgetwidget.cpp | 96 +++++++++++++++++++ .../plugins/debuggadget/debuggadgetwidget.h | 49 ++++++++++ .../src/plugins/debuggadget/debugplugin.cpp | 65 +++++++++++++ .../src/plugins/debuggadget/debugplugin.h | 47 +++++++++ ground/openpilotgcs/src/plugins/plugins.pro | 6 ++ .../uavsettingsimportexportfactory.cpp | 2 + .../uavsettingsimportexportfactory.h | 1 + 18 files changed, 557 insertions(+), 6 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/DebugGadget.pluginspec create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/debug.ui create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/debugengine.cpp create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/debugengine.h create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/debuggadget.cpp create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/debuggadget.h create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/debuggadget.pro create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.cpp create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.h create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.cpp create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.h create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/debugplugin.cpp create mode 100644 ground/openpilotgcs/src/plugins/debuggadget/debugplugin.h diff --git a/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp b/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp index 6a6ad66be..80e920c03 100644 --- a/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp @@ -39,6 +39,7 @@ #include "systemsettings.h" #include "mixersettings.h" #include "actuatorsettings.h" +#include /** Helper delegate for the custom mixer editor table. @@ -447,12 +448,7 @@ void ConfigAirframeWidget::updateCustomThrottle2CurveValue(QList list, d void ConfigAirframeWidget::refreshWidgetsValues() { if(!allObjectsUpdated()) - { - SystemSettings::GetInstance(getObjectManager())->requestUpdate(); - MixerSettings::GetInstance(getObjectManager())->requestUpdate(); - ActuatorSettings::GetInstance(getObjectManager())->requestUpdate(); return; - } bool dirty=isDirty(); // Get the Airframe type from the system settings: UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("SystemSettings"))); diff --git a/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp index f40225e71..5e579c971 100644 --- a/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp @@ -65,7 +65,7 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel { obj = objManager->getObject(QString(object)); Q_ASSERT(obj); - objectUpdates.insert(obj,false); + objectUpdates.insert(obj,true); connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*))); connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues())); } @@ -163,6 +163,7 @@ void ConfigTaskWidget::onAutopilotDisconnect() void ConfigTaskWidget::onAutopilotConnect() { + invalidateObjects(); dirty=false; isConnected=true; enableControls(true); diff --git a/ground/openpilotgcs/src/plugins/debuggadget/DebugGadget.pluginspec b/ground/openpilotgcs/src/plugins/debuggadget/DebugGadget.pluginspec new file mode 100644 index 000000000..05cea6931 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/DebugGadget.pluginspec @@ -0,0 +1,10 @@ + + The OpenPilot Project + (C) 2010 OpenPilot Project + The GNU Public License (GPL) Version 3 + An debug gadget + http://www.openpilot.org + + + + diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debug.ui b/ground/openpilotgcs/src/plugins/debuggadget/debug.ui new file mode 100644 index 000000000..72adcb7ee --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debug.ui @@ -0,0 +1,31 @@ + + + Form + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + Save to file + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debugengine.cpp b/ground/openpilotgcs/src/plugins/debuggadget/debugengine.cpp new file mode 100644 index 000000000..48ec18525 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debugengine.cpp @@ -0,0 +1,13 @@ +#include "debugengine.h" +debugengine::debugengine() +{ +} + +void debugengine::writeToStdErr(const QString &level, const QList &msgs) +{ + emit dbgMsgError(level,msgs); +} +void debugengine::writeToStdOut(const QString &level, const QList &msgs) +{ + emit dbgMsg(level,msgs); +} diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debugengine.h b/ground/openpilotgcs/src/plugins/debuggadget/debugengine.h new file mode 100644 index 000000000..5452f7590 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debugengine.h @@ -0,0 +1,18 @@ +#ifndef DEBUGENGINE_H +#define DEBUGENGINE_H +#include "qxtbasicstdloggerengine.h" +#include +class debugengine:public QObject,public QxtBasicSTDLoggerEngine +{ + Q_OBJECT +public: + debugengine(); +protected: + void writeToStdErr ( const QString & level, const QList & msgs ); + void writeToStdOut ( const QString & level, const QList & msgs ); +signals: + void dbgMsgError( const QString & level, const QList & msgs ); + void dbgMsg( const QString & level, const QList & msgs ); +}; + +#endif // DEBUGENGINE_H diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.cpp b/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.cpp new file mode 100644 index 000000000..05c147c03 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.cpp @@ -0,0 +1,39 @@ +/** + ****************************************************************************** + * + * @file debuggadget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * 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 "debuggadget.h" +#include "debuggadgetwidget.h" + +DebugGadget::DebugGadget(QString classId, DebugGadgetWidget *widget, QWidget *parent) : + IUAVGadget(classId, parent), + m_widget(widget) +{ +} + +DebugGadget::~DebugGadget() +{ + delete m_widget; +} diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.h b/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.h new file mode 100644 index 000000000..b39f8b5b5 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.h @@ -0,0 +1,59 @@ +/** + ****************************************************************************** + * + * @file debuggadget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * 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 + */ + +#ifndef DEBUGGADGET_H_ +#define DEBUGGADGET_H_ + +#include + +namespace Core { +class IUAVGadget; +} +//class QWidget; +//class QString; +class DebugGadgetWidget; + +using namespace Core; + +class DebugGadget : public Core::IUAVGadget +{ + Q_OBJECT +public: + DebugGadget(QString classId, DebugGadgetWidget *widget, QWidget *parent = 0); + ~DebugGadget(); + + QList context() const { return m_context; } + QWidget *widget() { return m_widget; } + QString contextHelpId() const { return QString(); } + +private: + QWidget *m_widget; + QList m_context; +}; + + +#endif // DEBUGGADGET_H_ diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.pro b/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.pro new file mode 100644 index 000000000..8434e723d --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.pro @@ -0,0 +1,21 @@ +TEMPLATE = lib +TARGET = DebugGadget + +include(../../openpilotgcsplugin.pri) +include(../../plugins/coreplugin/coreplugin.pri) +include(../../libs/libqxt/core/logengines.pri) +HEADERS += debugplugin.h \ + debugengine.h +HEADERS += debuggadget.h +HEADERS += debuggadgetwidget.h +HEADERS += debuggadgetfactory.h +SOURCES += debugplugin.cpp \ + debugengine.cpp +SOURCES += debuggadget.cpp +SOURCES += debuggadgetfactory.cpp +SOURCES += debuggadgetwidget.cpp + +OTHER_FILES += DebugGadget.pluginspec + +FORMS += \ + debug.ui diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.cpp b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.cpp new file mode 100644 index 000000000..f7d925b39 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.cpp @@ -0,0 +1,47 @@ +/** + ****************************************************************************** + * + * @file debuggadgetfactory.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * 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 "debuggadgetfactory.h" +#include "debuggadgetwidget.h" +#include "debuggadget.h" +#include + +DebugGadgetFactory::DebugGadgetFactory(QObject *parent) : + IUAVGadgetFactory(QString("DebugGadget"), + tr("DebugGadget"), + parent) +{ +} + +DebugGadgetFactory::~DebugGadgetFactory() +{ + +} + +IUAVGadget* DebugGadgetFactory::createGadget(QWidget *parent) { + DebugGadgetWidget* gadgetWidget = new DebugGadgetWidget(parent); + return new DebugGadget(QString("DebugGadget"), gadgetWidget, parent); +} diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.h b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.h new file mode 100644 index 000000000..186fca5f6 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.h @@ -0,0 +1,50 @@ +/** + ****************************************************************************** + * + * @file debuggadgetfactory.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * 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 + */ + +#ifndef DEBUGGADGETFACTORY_H_ +#define DEBUGGADGETFACTORY_H_ + +#include + +namespace Core { +class IUAVGadget; +class IUAVGadgetFactory; +} + +using namespace Core; + +class DebugGadgetFactory : public IUAVGadgetFactory +{ + Q_OBJECT +public: + DebugGadgetFactory(QObject *parent = 0); + ~DebugGadgetFactory(); + + IUAVGadget *createGadget(QWidget *parent); +}; + +#endif // DEBUGGADGETFACTORY_H_ diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.cpp b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.cpp new file mode 100644 index 000000000..f7c625a87 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.cpp @@ -0,0 +1,96 @@ +/** + ****************************************************************************** + * + * @file debuggadgetwidget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * 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 "debuggadgetwidget.h" + +#include +#include +#include +#include +#include +#include +#include "qxtlogger.h" +#include "debugengine.h" +#include +#include +#include +#include +DebugGadgetWidget::DebugGadgetWidget(QWidget *parent) : QLabel(parent) +{ + m_config = new Ui_Form(); + m_config->setupUi(this); + debugengine * de=new debugengine(); + QxtLogger::getInstance()->addLoggerEngine("debugplugin", de); + connect(de,SIGNAL(dbgMsg(QString,QList)),this,SLOT(dbgMsg(QString,QList))); + connect(de,SIGNAL(dbgMsgError(QString,QList)),this,SLOT(dbgMsgError(QString,QList))); + connect(m_config->pushButton,SIGNAL(clicked()),this,SLOT(saveLog())); +} + +DebugGadgetWidget::~DebugGadgetWidget() +{ + // Do nothing +} + +void DebugGadgetWidget::dbgMsg(const QString &level, const QList &msgs) +{ + m_config->plainTextEdit->setTextColor(Qt::black); + foreach(QVariant str,msgs) + { + m_config->plainTextEdit->append(QString("[%0]%1").arg(level).arg(str.toString())); + } + QScrollBar *sb = m_config->plainTextEdit->verticalScrollBar(); + sb->setValue(sb->maximum()); +} + +void DebugGadgetWidget::dbgMsgError(const QString &level, const QList &msgs) +{ + m_config->plainTextEdit->setTextColor(Qt::red); + foreach(QVariant str,msgs) + { + m_config->plainTextEdit->append(QString("[%0]%1").arg(level).arg(str.toString())); + } + QScrollBar *sb = m_config->plainTextEdit->verticalScrollBar(); + sb->setValue(sb->maximum()); +} +void DebugGadgetWidget::saveLog() +{ + QString fileName = QFileDialog::getSaveFileName(0, tr("Save log File As"), ""); + if (fileName.isEmpty()) { + return; + } + + QFile file(fileName); + if (file.open(QIODevice::WriteOnly) && + (file.write(m_config->plainTextEdit->toHtml().toAscii()) != -1)) { + file.close(); + } else { + QMessageBox::critical(0, + tr("Log Save"), + tr("Unable to save log: ") + fileName, + QMessageBox::Ok); + return; + } +} diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.h b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.h new file mode 100644 index 000000000..ed71f73c2 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.h @@ -0,0 +1,49 @@ +/** + ****************************************************************************** + * + * @file debuggadgetwidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * 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 + */ + +#ifndef DEBUGGADGETWIDGET_H_ +#define DEBUGGADGETWIDGET_H_ + +#include +#include "ui_debug.h" +class DebugGadgetWidget : public QLabel +{ + Q_OBJECT + +public: + DebugGadgetWidget(QWidget *parent = 0); + ~DebugGadgetWidget(); + +private: + Ui_Form *m_config; +private slots: + void saveLog(); + void dbgMsgError( const QString & level, const QList & msgs ); + void dbgMsg( const QString & level, const QList & msgs ); +}; + +#endif /* DEBUGGADGETWIDGET_H_ */ diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debugplugin.cpp b/ground/openpilotgcs/src/plugins/debuggadget/debugplugin.cpp new file mode 100644 index 000000000..f83395ef7 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debugplugin.cpp @@ -0,0 +1,65 @@ +/** + ****************************************************************************** + * + * @file debugplugin.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * 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 "debugplugin.h" +#include "debuggadgetfactory.h" +#include +#include +#include +#include + + +DebugPlugin::DebugPlugin() +{ + // Do nothing +} + +DebugPlugin::~DebugPlugin() +{ + // Do nothing +} + +bool DebugPlugin::initialize(const QStringList& args, QString *errMsg) +{ + Q_UNUSED(args); + Q_UNUSED(errMsg); + mf = new DebugGadgetFactory(this); + addAutoReleasedObject(mf); + + return true; +} + +void DebugPlugin::extensionsInitialized() +{ + // Do nothing +} + +void DebugPlugin::shutdown() +{ + // Do nothing +} +Q_EXPORT_PLUGIN(DebugPlugin) + diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debugplugin.h b/ground/openpilotgcs/src/plugins/debuggadget/debugplugin.h new file mode 100644 index 000000000..9cdbefd02 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debugplugin.h @@ -0,0 +1,47 @@ +/** + ****************************************************************************** + * + * @file debugplugin.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * 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 + */ + +#ifndef DEBUGPLUGIN_H_ +#define DEBUGPLUGIN_H_ + +#include + +class DebugGadgetFactory; + +class DebugPlugin : public ExtensionSystem::IPlugin +{ +public: + DebugPlugin(); + ~DebugPlugin(); + + void extensionsInitialized(); + bool initialize(const QStringList & arguments, QString * errorString); + void shutdown(); +private: + DebugGadgetFactory *mf; +}; +#endif /* DEBUGPLUGIN_H_ */ diff --git a/ground/openpilotgcs/src/plugins/plugins.pro b/ground/openpilotgcs/src/plugins/plugins.pro index 12e7d7c43..8079fa880 100644 --- a/ground/openpilotgcs/src/plugins/plugins.pro +++ b/ground/openpilotgcs/src/plugins/plugins.pro @@ -19,6 +19,12 @@ plugin_emptygadget.subdir = emptygadget plugin_emptygadget.depends = plugin_coreplugin SUBDIRS += plugin_emptygadget +# UAV Settings Import/Export plugin +plugin_debuggadget.subdir = debuggadget +#plugin_debughelper.depends = plugin_coreplugin +#plugin_debughelper.depends += plugin_uavobjects +SUBDIRS += plugin_debuggadget + # Welcome plugin plugin_welcome.subdir = welcome plugin_welcome.depends = plugin_coreplugin diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp index be81222fe..ff6eb233b 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp @@ -115,6 +115,7 @@ void UAVSettingsImportExportFactory::importUAVSettings() } file.close(); emit importAboutToBegin(); + qDebug()<<"Import about to begin"; QDomElement root = doc.documentElement(); if (root.tagName() != "settings") { QMessageBox msgBox; @@ -188,6 +189,7 @@ void UAVSettingsImportExportFactory::importUAVSettings() } node = node.nextSibling(); } + qDebug()<<"End import"; swui.exec(); diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h index 2ef5f803e..a130d5c4a 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h @@ -48,6 +48,7 @@ private slots: void exportUAVData(); signals: void importAboutToBegin(); + void importEnded(); }; From 898d3c980d27d01509e13fc9decee52024df5449 Mon Sep 17 00:00:00 2001 From: zedamota Date: Tue, 27 Sep 2011 22:10:39 +0100 Subject: [PATCH 05/18] Cosmetic changes to the Debug plugin One more fix to the mixer bug --- .../plugins/config/configairframewidget.cpp | 26 ++++++++++++++++--- .../src/plugins/config/configtaskwidget.cpp | 1 + .../src/plugins/config/smartsavebutton.cpp | 5 ++-- .../plugins/debuggadget/debuggadgetwidget.cpp | 20 +++++++------- 4 files changed, 36 insertions(+), 16 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp b/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp index 80e920c03..96393b381 100644 --- a/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp @@ -1522,6 +1522,16 @@ bool ConfigAirframeWidget::setupFrameVtail() */ bool ConfigAirframeWidget::setupMixer(double mixerFactors[8][3]) { + qDebug()<<"Mixer factors"; + qDebug()< mmList; mmList << m_aircraft->multiMotor1 << m_aircraft->multiMotor2 << m_aircraft->multiMotor3 @@ -1539,11 +1549,15 @@ bool ConfigAirframeWidget::setupMixer(double mixerFactors[8][3]) double pFactor = (double)m_aircraft->mrPitchMixLevel->value()/100; double rFactor = (double)m_aircraft->mrRollMixLevel->value()/100; double yFactor = (double)m_aircraft->mrYawMixLevel->value()/100; + qDebug()<currentIndex()-1; - if (channel > -1) - setupQuadMotor(channel, mixerFactors[i][0]*pFactor, - rFactor*mixerFactors[i][1], yFactor*mixerFactors[i][2]); + if(mmList.at(i)->isEnabled()) + { + int channel = mmList.at(i)->currentIndex()-1; + if (channel > -1) + setupQuadMotor(channel, mixerFactors[i][0]*pFactor, + rFactor*mixerFactors[i][1], yFactor*mixerFactors[i][2]); + } } // obj->updated(); return true; @@ -1555,6 +1569,7 @@ bool ConfigAirframeWidget::setupMixer(double mixerFactors[8][3]) */ void ConfigAirframeWidget::setupQuadMotor(int channel, double pitch, double roll, double yaw) { + qDebug()<(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(obj); UAVObjectField *field = obj->getField(mixerTypes.at(channel)); @@ -1566,10 +1581,13 @@ void ConfigAirframeWidget::setupQuadMotor(int channel, double pitch, double roll field->setValue(127, ti); ti = field->getElementNames().indexOf("Roll"); field->setValue(roll*127,ti); + qDebug()<<"Set roll="<getElementNames().indexOf("Pitch"); field->setValue(pitch*127,ti); + qDebug()<<"Set pitch="<getElementNames().indexOf("Yaw"); field->setValue(yaw*127,ti); + qDebug()<<"Set yaw="<getName(); + qDebug()<<"Object upload error:"<getName(); error=true; continue; } @@ -59,7 +59,7 @@ void smartSaveButton::processClick() { for(int i=0;i<3;++i) { - //qDebug()<<"try to save:"<getName(); + qDebug()<<"try to save:"<getName(); connect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); utilMngr->saveObjectToSD(obj); @@ -73,6 +73,7 @@ void smartSaveButton::processClick() } if(sv_result==false) { + qDebug()<<"failed to save:"<getName(); error=true; } } diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.cpp b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.cpp index f7c625a87..34043c806 100644 --- a/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.cpp @@ -38,6 +38,7 @@ #include #include #include +#include DebugGadgetWidget::DebugGadgetWidget(QWidget *parent) : QLabel(parent) { m_config = new Ui_Form(); @@ -56,22 +57,21 @@ DebugGadgetWidget::~DebugGadgetWidget() void DebugGadgetWidget::dbgMsg(const QString &level, const QList &msgs) { - m_config->plainTextEdit->setTextColor(Qt::black); - foreach(QVariant str,msgs) - { - m_config->plainTextEdit->append(QString("[%0]%1").arg(level).arg(str.toString())); - } + m_config->plainTextEdit->setTextColor(Qt::red); + + m_config->plainTextEdit->append(QString("%2[%0]%1").arg(level).arg(msgs[0].toString()).arg(QTime::currentTime().toString())); + QScrollBar *sb = m_config->plainTextEdit->verticalScrollBar(); sb->setValue(sb->maximum()); } void DebugGadgetWidget::dbgMsgError(const QString &level, const QList &msgs) { - m_config->plainTextEdit->setTextColor(Qt::red); - foreach(QVariant str,msgs) - { - m_config->plainTextEdit->append(QString("[%0]%1").arg(level).arg(str.toString())); - } + m_config->plainTextEdit->setTextColor(Qt::black); + + + m_config->plainTextEdit->append(QString("%2[%0]%1").arg(level).arg(msgs[0].toString()).arg(QTime::currentTime().toString())); + QScrollBar *sb = m_config->plainTextEdit->verticalScrollBar(); sb->setValue(sb->maximum()); } From de8478718c7a63769ee33f0e5cec1b8fac301110 Mon Sep 17 00:00:00 2001 From: Edouard Lafargue Date: Wed, 5 Oct 2011 00:38:56 +0200 Subject: [PATCH 06/18] Attempt to make USB faster on Mac. Breaks the Firmware upload system!!! --- .../src/plugins/rawhid/pjrc_rawhid.h | 9 ++- .../src/plugins/rawhid/pjrc_rawhid_mac.cpp | 55 +++++++++++++------ 2 files changed, 45 insertions(+), 19 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid.h b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid.h index b8e2459a2..49436cd18 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid.h +++ b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid.h @@ -37,6 +37,7 @@ #if defined( Q_OS_MAC) +#include // todo: #elif defined(Q_OS_UNIX) @@ -104,10 +105,16 @@ public: void mytest(int num); signals: void deviceUnplugged(int);//just to make pips changes compile +#if defined( Q_OS_MAC) +public slots: + void timeout_callback(); +#endif + private: #if defined( Q_OS_MAC) - // todo: + int timeout_occurred; + QTimer m_timer; #elif defined(Q_OS_UNIX) //#elif defined(Q_OS_LINUX) diff --git a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp index 34c78fa8f..29d0b9f0d 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp +++ b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp @@ -44,6 +44,17 @@ #include #include #include +#include +#include + +class delay : public QThread +{ +public: + static void msleep(unsigned long msecs) + { + QThread::msleep(msecs); + } +}; #define BUFFER_SIZE 64 @@ -75,7 +86,6 @@ static void free_all_hid(void); static void hid_close(hid_t *); static void attach_callback(void *, IOReturn, void *, IOHIDDeviceRef); static void detach_callback(void *, IOReturn, void *hid_mgr, IOHIDDeviceRef dev); -static void timeout_callback(CFRunLoopTimerRef, void *); static void input_callback(void *, IOReturn, void *, IOHIDReportType, uint32_t, uint8_t *, CFIndex); static void output_callback(hid_t *context, IOReturn ret, void *sender, IOHIDReportType type, uint32_t id, uint8_t *data, CFIndex len); @@ -109,6 +119,8 @@ int pjrc_rawhid::open(int max, int vid, int pid, int usage_page, int usage) hid_t *p; int count=0; + connect(&m_timer, SIGNAL(timeout()), this, SLOT(timeout_callback())); + if (first_hid) free_all_hid(); //printf("pjrc_rawhid_open, max=%d\n", max); if (max < 1) return 0; @@ -185,9 +197,7 @@ int pjrc_rawhid::receive(int num, void *buf, int len, int timeout) { hid_t *hid; buffer_t *b; - CFRunLoopTimerRef timer=NULL; - CFRunLoopTimerContext context; - int ret=0, timeout_occurred=0; + int ret=0; if (len < 1) return 0; hid = get_hid(num); @@ -197,21 +207,28 @@ int pjrc_rawhid::receive(int num, void *buf, int len, int timeout) memcpy(buf, b->buf, len); hid->first_buffer = b->next; free(b); + //printf("packet already, returning before loop"); return len; } - memset(&context, 0, sizeof(context)); - context.info = &timeout_occurred; - timer = CFRunLoopTimerCreate(NULL, CFAbsoluteTimeGetCurrent() + - (double)timeout / 1000.0, 0, 0, 0, timeout_callback, &context); - CFRunLoopAddTimer(CFRunLoopGetCurrent(), timer, kCFRunLoopDefaultMode); - while (1) { + + // This does not work while in a "while" loop!! Come on... + // BEWARE: this area is broken. + // We need a way (probably thread?) to wait for USB data + // while also accepting a timeout. + timeout_occurred = 1; + m_timer.start(timeout); + while (true) { + // CFRunLoopRun does not work properly with Qt's event loop... CFRunLoopRun(); + printf("."); + delay::msleep(20); if ((b = hid->first_buffer) != NULL) { if (len > b->len) len = b->len; memcpy(buf, b->buf, len); hid->first_buffer = b->next; free(b); ret = len; + // printf("got packet, exit waiting loop with %i bytes",ret); break; } if (!hid->open) { @@ -219,10 +236,12 @@ int pjrc_rawhid::receive(int num, void *buf, int len, int timeout) ret = -1; break; } - if (timeout_occurred) break; + if (timeout_occurred) { + qDebug("Timeout while waiting for packet"); + break; + } } - CFRunLoopTimerInvalidate(timer); - CFRelease(timer); + m_timer.stop(); return ret; } @@ -335,10 +354,11 @@ static void input_callback(void *context, IOReturn ret, void *sender, IOHIDRepor buffer_t *n; hid_t *hid; - printf("input_callback, report id: %i buf: %x %x, len: %d\n", id, data[0], data[1], len); + //printf("input_callback, ret: %i - report id: %i buf: %x %x, len: %d\n", ret, id, data[0], data[1], len); if (ret != kIOReturnSuccess || len < 1) return; hid = (hid_t*)context; if (!hid || hid->ref != sender) return; + printf("Processing packet"); n = (buffer_t *)malloc(sizeof(buffer_t)); if (!n) return; if (len > BUFFER_SIZE) len = BUFFER_SIZE; @@ -355,11 +375,10 @@ static void input_callback(void *context, IOReturn ret, void *sender, IOHIDRepor CFRunLoopStop(CFRunLoopGetCurrent()); } -static void timeout_callback(CFRunLoopTimerRef timer, void *info) +void pjrc_rawhid::timeout_callback() { - printf("timeout_callback\n"); - *(int *)info = 1; - CFRunLoopStop(CFRunLoopGetCurrent()); + qDebug("[pjrc_rawhid_mac] timeout_callback"); + timeout_occurred = 1; } static void add_hid(hid_t *h) From 5dc0f397a6e64cfd6621ff5d5d5ec07a4471106c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 7 Oct 2011 14:08:56 -0500 Subject: [PATCH 07/18] OP-499 Erase settings bug: Make hte flash chip read a wrong value for 1 second before wiping settings. --- flight/PiOS/Common/pios_flashfs_objlist.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/flight/PiOS/Common/pios_flashfs_objlist.c b/flight/PiOS/Common/pios_flashfs_objlist.c index 2b2fe06fa..b252ef81e 100644 --- a/flight/PiOS/Common/pios_flashfs_objlist.c +++ b/flight/PiOS/Common/pios_flashfs_objlist.c @@ -61,7 +61,7 @@ struct fileHeader { #define OBJECT_TABLE_START 0x00000010 #define OBJECT_TABLE_END 0x00001000 #define SECTOR_SIZE 0x00001000 -#define MAX_BADMAGIC 4 +#define MAX_BADMAGIC 1000 /** * @brief Initialize the flash object setting FS @@ -72,7 +72,7 @@ int32_t PIOS_FLASHFS_Init() // Check for valid object table or create one uint32_t object_table_magic; - uint8_t magic_fail_count = 0; + uint32_t magic_fail_count = 0; bool magic_good = false; while(!magic_good) { @@ -85,7 +85,7 @@ int32_t PIOS_FLASHFS_Init() magic_fail_count = 0; magic_good = true; } else { - PIOS_DELAY_WaituS(100); + PIOS_DELAY_WaituS(1000); } } From a8a7cce7d8ba401804382d8240403609f98b158b Mon Sep 17 00:00:00 2001 From: zedamota Date: Sat, 8 Oct 2011 18:28:46 +0100 Subject: [PATCH 08/18] test commit --- HISTORY.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/HISTORY.txt b/HISTORY.txt index 98193adce..1c77ee0a6 100644 --- a/HISTORY.txt +++ b/HISTORY.txt @@ -56,3 +56,4 @@ selected from ManualControlSettings.InputMode and the aircraft must be rebooted after changing this. Also for CopterControl the HwSettings object must indicate which modules are connected to which ports. PPM currently not working. + From 0f1a6264de51948de685f54ca59afcf2a9379166 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 8 Oct 2011 14:12:53 -0500 Subject: [PATCH 09/18] Fix jtag programming of bootloader --- flight/Bootloaders/AHRS/Makefile | 2 +- flight/Bootloaders/CopterControl/Makefile | 2 +- flight/Bootloaders/OpenPilot/Makefile | 2 +- flight/Bootloaders/PipXtreme/Makefile | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/flight/Bootloaders/AHRS/Makefile b/flight/Bootloaders/AHRS/Makefile index 18bf8a269..fe52f8ae0 100644 --- a/flight/Bootloaders/AHRS/Makefile +++ b/flight/Bootloaders/AHRS/Makefile @@ -354,7 +354,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/Bootloaders/CopterControl/Makefile b/flight/Bootloaders/CopterControl/Makefile index 99521020d..cc98fb777 100644 --- a/flight/Bootloaders/CopterControl/Makefile +++ b/flight/Bootloaders/CopterControl/Makefile @@ -413,7 +413,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/Bootloaders/OpenPilot/Makefile b/flight/Bootloaders/OpenPilot/Makefile index cad11dedf..d4a944c0d 100644 --- a/flight/Bootloaders/OpenPilot/Makefile +++ b/flight/Bootloaders/OpenPilot/Makefile @@ -419,7 +419,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/Bootloaders/PipXtreme/Makefile b/flight/Bootloaders/PipXtreme/Makefile index 19b651a5f..94d7206ed 100644 --- a/flight/Bootloaders/PipXtreme/Makefile +++ b/flight/Bootloaders/PipXtreme/Makefile @@ -414,7 +414,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino elf: $(OUTDIR)/$(TARGET).elf From 7da8cb2079c3c59aee0d10f51cc15ff2db3f39f8 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 8 Oct 2011 14:15:48 -0500 Subject: [PATCH 10/18] CC: After attitude calibration always reenable BiasCorrectGyro. Fixes odd bug if people have it crash in the middle. --- .../openpilotgcs/src/plugins/config/configccattitudewidget.cpp | 3 +-- .../openpilotgcs/src/plugins/config/configccattitudewidget.h | 1 - 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp index c659180af..6ad28c666 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp @@ -98,7 +98,7 @@ void ConfigCCAttitudeWidget::attitudeRawUpdated(UAVObject * obj) { attitudeSettingsData.GyroBias[0] = -x_gyro_bias; attitudeSettingsData.GyroBias[1] = -y_gyro_bias; attitudeSettingsData.GyroBias[2] = -z_gyro_bias; - attitudeSettingsData.BiasCorrectGyro = initialBiasCorrected; + attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE; AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData); } else { @@ -134,7 +134,6 @@ void ConfigCCAttitudeWidget::startAccelCalibration() { // Disable gyro bias correction to see raw data AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData(); - initialBiasCorrected = attitudeSettingsData.BiasCorrectGyro; attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE; AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData); diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h index 09dfdb222..af107f670 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h @@ -57,7 +57,6 @@ private: Ui_ccattitude *ui; QTimer timer; UAVObject::Metadata initialMdata; - quint8 initialBiasCorrected; int updates; From 6514ea526227392c78b1ad79b5a579405cf01d06 Mon Sep 17 00:00:00 2001 From: Edouard Lafargue Date: Tue, 11 Oct 2011 00:10:27 +0200 Subject: [PATCH 11/18] Finally, a fix for the Mac UAVTalk issues: it was all caused by a wrong RunLoop pointer reference because of multithreading. --- .../src/plugins/rawhid/pjrc_rawhid.h | 8 +- .../src/plugins/rawhid/pjrc_rawhid_mac.cpp | 114 ++++++++++-------- 2 files changed, 63 insertions(+), 59 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid.h b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid.h index 49436cd18..3ff096db5 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid.h +++ b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid.h @@ -37,8 +37,6 @@ #if defined( Q_OS_MAC) -#include -// todo: #elif defined(Q_OS_UNIX) //#elif defined(Q_OS_LINUX) @@ -106,16 +104,12 @@ public: signals: void deviceUnplugged(int);//just to make pips changes compile #if defined( Q_OS_MAC) -public slots: - void timeout_callback(); + #endif private: #if defined( Q_OS_MAC) - int timeout_occurred; - QTimer m_timer; - #elif defined(Q_OS_UNIX) //#elif defined(Q_OS_LINUX) diff --git a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp index 29d0b9f0d..382c43829 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp +++ b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp @@ -46,6 +46,7 @@ #include #include #include +#include class delay : public QThread { @@ -65,6 +66,8 @@ typedef struct hid_struct hid_t; typedef struct buffer_struct buffer_t; static hid_t *first_hid = NULL; static hid_t *last_hid = NULL; +// Make sure we use the correct runloop +CFRunLoopRef the_correct_runloop = NULL; struct hid_struct { IOHIDDeviceRef ref; int open; @@ -88,6 +91,8 @@ static void attach_callback(void *, IOReturn, void *, IOHIDDeviceRef); static void detach_callback(void *, IOReturn, void *hid_mgr, IOHIDDeviceRef dev); static void input_callback(void *, IOReturn, void *, IOHIDReportType, uint32_t, uint8_t *, CFIndex); static void output_callback(hid_t *context, IOReturn ret, void *sender, IOHIDReportType type, uint32_t id, uint8_t *data, CFIndex len); +static void timeout_callback(CFRunLoopTimerRef, void *); + pjrc_rawhid::pjrc_rawhid() { @@ -119,8 +124,6 @@ int pjrc_rawhid::open(int max, int vid, int pid, int usage_page, int usage) hid_t *p; int count=0; - connect(&m_timer, SIGNAL(timeout()), this, SLOT(timeout_callback())); - if (first_hid) free_all_hid(); //printf("pjrc_rawhid_open, max=%d\n", max); if (max < 1) return 0; @@ -176,6 +179,8 @@ int pjrc_rawhid::open(int max, int vid, int pid, int usage_page, int usage) CFRelease(hid_manager); return 0; } + // Set the run loop reference: + the_correct_runloop = CFRunLoopGetCurrent(); printf("run loop\n"); // let it do the callback for all devices while (CFRunLoopRunInMode(kCFRunLoopDefaultMode, 0, true) == kCFRunLoopRunHandledSource) ; @@ -195,54 +200,56 @@ int pjrc_rawhid::open(int max, int vid, int pid, int usage_page, int usage) // int pjrc_rawhid::receive(int num, void *buf, int len, int timeout) { - hid_t *hid; - buffer_t *b; - int ret=0; + hid_t *hid; + buffer_t *b; + CFRunLoopTimerRef timer=NULL; + CFRunLoopTimerContext context; + int ret=0, timeout_occurred=0; - if (len < 1) return 0; - hid = get_hid(num); - if (!hid || !hid->open) return -1; - if ((b = hid->first_buffer) != NULL) { - if (len > b->len) len = b->len; - memcpy(buf, b->buf, len); - hid->first_buffer = b->next; - free(b); - //printf("packet already, returning before loop"); - return len; - } + if (len < 1) return 0; + hid = get_hid(num); + if (!hid || !hid->open) return -1; + if ((b = hid->first_buffer) != NULL) { + if (len > b->len) len = b->len; + memcpy(buf, b->buf, len); + hid->first_buffer = b->next; + free(b); + return len; + } + memset(&context, 0, sizeof(context)); + context.info = &timeout_occurred; + timer = CFRunLoopTimerCreate(NULL, CFAbsoluteTimeGetCurrent() + + (double)timeout / 1000.0, 0, 0, 0, timeout_callback, &context); + CFRunLoopAddTimer(CFRunLoopGetCurrent(), timer, kCFRunLoopDefaultMode); + the_correct_runloop = CFRunLoopGetCurrent(); + //qDebug("--"); + while (1) { + //qDebug("."); + CFRunLoopRun(); // Found the problem: somehow the input_callback does not + // stop this CFRunLoopRun because it is hooked to a different run loop !!! + // Hence the use of the "correct_runloop" variable above. + //qDebug(" .."); - // This does not work while in a "while" loop!! Come on... - // BEWARE: this area is broken. - // We need a way (probably thread?) to wait for USB data - // while also accepting a timeout. - timeout_occurred = 1; - m_timer.start(timeout); - while (true) { - // CFRunLoopRun does not work properly with Qt's event loop... - CFRunLoopRun(); - printf("."); - delay::msleep(20); - if ((b = hid->first_buffer) != NULL) { - if (len > b->len) len = b->len; - memcpy(buf, b->buf, len); - hid->first_buffer = b->next; - free(b); - ret = len; - // printf("got packet, exit waiting loop with %i bytes",ret); + if ((b = hid->first_buffer) != NULL) { + if (len > b->len) len = b->len; + memcpy(buf, b->buf, len); + hid->first_buffer = b->next; + free(b); + ret = len; + //qDebug("*************"); + break; + } + if (!hid->open) { + printf("pjrc_rawhid_recv, device not open\n"); + ret = -1; + break; + } + if (timeout_occurred) break; - } - if (!hid->open) { - printf("pjrc_rawhid_recv, device not open\n"); - ret = -1; - break; - } - if (timeout_occurred) { - qDebug("Timeout while waiting for packet"); - break; - } - } - m_timer.stop(); - return ret; + } + CFRunLoopTimerInvalidate(timer); + CFRelease(timer); + return ret; } // send - send a packet @@ -354,7 +361,7 @@ static void input_callback(void *context, IOReturn ret, void *sender, IOHIDRepor buffer_t *n; hid_t *hid; - //printf("input_callback, ret: %i - report id: %i buf: %x %x, len: %d\n", ret, id, data[0], data[1], len); + //qDebug("input_callback, ret: %i - report id: %i buf: %x %x, len: %d\n", ret, id, data[0], data[1], len); if (ret != kIOReturnSuccess || len < 1) return; hid = (hid_t*)context; if (!hid || hid->ref != sender) return; @@ -372,13 +379,16 @@ static void input_callback(void *context, IOReturn ret, void *sender, IOHIDRepor hid->last_buffer->next = n; hid->last_buffer = n; } - CFRunLoopStop(CFRunLoopGetCurrent()); + //qDebug() << "Stop CFRunLoop from input_callback" << CFRunLoopGetCurrent(); + CFRunLoopStop(the_correct_runloop); } -void pjrc_rawhid::timeout_callback() +static void timeout_callback(CFRunLoopTimerRef timer, void *info) { - qDebug("[pjrc_rawhid_mac] timeout_callback"); - timeout_occurred = 1; + //qDebug("timeout_callback\n"); + *(int *)info = 1; + //qDebug() << "Stop CFRunLoop from timeout_callback" << CFRunLoopGetCurrent(); + CFRunLoopStop(CFRunLoopGetCurrent()); } static void add_hid(hid_t *h) From cf52c9024aac2a26faa90f0e1a9d645d2ece26c2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 11 Oct 2011 10:24:38 -0500 Subject: [PATCH 12/18] Update history --- HISTORY.txt | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/HISTORY.txt b/HISTORY.txt index 98193adce..7eba13a9a 100644 --- a/HISTORY.txt +++ b/HISTORY.txt @@ -1,5 +1,12 @@ Short summary of changes. For a complete list see the git log. +2011-10-11 +Fix for the Mac telemetry rates and specifically how long enumeration took. + +2011-10-08 +Make the flash chip need to be have bad magic for a full second before erasing +settings. Should avoid random lost settings. + 2011-09-12 Max rate now ONLY applies to attitude and axis lock mode. Manual rate is the only term that limits the rate mode now (and in axis lock when you push stick From 425bc5abbe6257a8b60d6441a7b7b0f5b15be54a Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Tue, 11 Oct 2011 18:07:04 +0200 Subject: [PATCH 13/18] PiOS.posix: PIOS_RCVR : fix posix port of pios_rcvr to allow compilation on 64bit systems --- flight/Modules/ManualControl/manualcontrol.c | 2 +- flight/OpenPilot/System/pios_board_posix.c | 12 +++- flight/PiOS.posix/inc/pios_rcvr.h | 21 ++++--- flight/PiOS.posix/posix/pios_rcvr.c | 65 ++++++++++++++------ 4 files changed, 68 insertions(+), 32 deletions(-) diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index e8b18fefb..6186a6af9 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -456,7 +456,7 @@ static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm break; } - ReceiverActivityActiveGroupSet(&group); + ReceiverActivityActiveGroupSet((uint8_t*)&group); ReceiverActivityActiveChannelSet(&channel); activity_updated = true; } diff --git a/flight/OpenPilot/System/pios_board_posix.c b/flight/OpenPilot/System/pios_board_posix.c index 37fadd760..48d6839bc 100644 --- a/flight/OpenPilot/System/pios_board_posix.c +++ b/flight/OpenPilot/System/pios_board_posix.c @@ -33,11 +33,19 @@ #include "attitudeactual.h" #include "positionactual.h" #include "velocityactual.h" +#include "manualcontrolsettings.h" +#if defined(PIOS_INCLUDE_RCVR) #include "pios_rcvr_priv.h" -struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_CHANNELS]; -uint32_t pios_rcvr_max_channel; +/* One slot per selectable receiver group. + * eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS + * NOTE: No slot in this map for NONE. + */ +uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; + +#endif /* PIOS_INCLUDE_RCVR */ + void Stack_Change() { } diff --git a/flight/PiOS.posix/inc/pios_rcvr.h b/flight/PiOS.posix/inc/pios_rcvr.h index a32160894..ab493cd35 100644 --- a/flight/PiOS.posix/inc/pios_rcvr.h +++ b/flight/PiOS.posix/inc/pios_rcvr.h @@ -31,21 +31,24 @@ #ifndef PIOS_RCVR_H #define PIOS_RCVR_H -struct pios_rcvr_channel_map { - uint32_t id; - uint8_t channel; -}; - -extern struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[]; - struct pios_rcvr_driver { - void (*init)(uint32_t id); - int32_t (*read)(uint32_t id, uint8_t channel); + void (*init)(uint32_t id); + int32_t (*read)(uint32_t id, uint8_t channel); }; /* Public Functions */ extern int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel); +/*! Define error codes for PIOS_RCVR_Get */ +enum PIOS_RCVR_errors { + /*! Indicates that a failsafe condition or missing receiver detected for that channel */ + PIOS_RCVR_TIMEOUT = 0, + /*! Channel is invalid for this driver (usually out of range supported) */ + PIOS_RCVR_INVALID = -1, + /*! Indicates that the driver for this channel has not been initialized */ + PIOS_RCVR_NODRIVER = -2 +}; + #endif /* PIOS_RCVR_H */ /** diff --git a/flight/PiOS.posix/posix/pios_rcvr.c b/flight/PiOS.posix/posix/pios_rcvr.c index 652730547..719cb9769 100644 --- a/flight/PiOS.posix/posix/pios_rcvr.c +++ b/flight/PiOS.posix/posix/pios_rcvr.c @@ -21,32 +21,39 @@ static bool PIOS_RCVR_validate(struct pios_rcvr_dev * rcvr_dev) } #if defined(PIOS_INCLUDE_FREERTOS) && 0 -static struct pios_rcvr_dev * PIOS_RCVR_alloc(void) -{ - struct pios_rcvr_dev * rcvr_dev; - - rcvr_dev = (struct pios_rcvr_dev *)malloc(sizeof(*rcvr_dev)); - if (!rcvr_dev) return (NULL); - - rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC; - return(rcvr_dev); -} +//static struct pios_rcvr_dev * PIOS_RCVR_alloc(void) +//{ +// struct pios_rcvr_dev * rcvr_dev; +// +// rcvr_dev = (struct pios_rcvr_dev *)pvPortMalloc(sizeof(*rcvr_dev)); +// if (!rcvr_dev) return (NULL); +// +// rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC; +// return(rcvr_dev); +//} #else static struct pios_rcvr_dev pios_rcvr_devs[PIOS_RCVR_MAX_DEVS]; static uint8_t pios_rcvr_num_devs; -static struct pios_rcvr_dev * PIOS_RCVR_alloc(void) +static uint32_t PIOS_RCVR_alloc(void) { struct pios_rcvr_dev * rcvr_dev; if (pios_rcvr_num_devs >= PIOS_RCVR_MAX_DEVS) { - return (NULL); + return (PIOS_RCVR_MAX_DEVS+1); } rcvr_dev = &pios_rcvr_devs[pios_rcvr_num_devs++]; rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC; - return (rcvr_dev); + return (pios_rcvr_num_devs); } +static struct pios_rcvr_dev * PIOS_RCVR_find_dev(uint32_t rcvr_dev_id) +{ + if (!rcvr_dev_id) return NULL; + if (rcvr_dev_id>pios_rcvr_num_devs+1) return NULL; + return &pios_rcvr_devs[rcvr_dev_id-1]; +} + #endif /** @@ -56,35 +63,53 @@ static struct pios_rcvr_dev * PIOS_RCVR_alloc(void) * \param[in] id * \return < 0 if initialisation failed */ -int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id) +int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, uint32_t lower_id) { PIOS_DEBUG_Assert(rcvr_id); PIOS_DEBUG_Assert(driver); + uint32_t rcvr_dev_id; struct pios_rcvr_dev * rcvr_dev; - rcvr_dev = (struct pios_rcvr_dev *) PIOS_RCVR_alloc(); + rcvr_dev_id = PIOS_RCVR_alloc(); + rcvr_dev = PIOS_RCVR_find_dev(rcvr_dev_id); if (!rcvr_dev) goto out_fail; rcvr_dev->driver = driver; rcvr_dev->lower_id = lower_id; - - *rcvr_id = pios_rcvr_num_devs - 1; - + *rcvr_id = rcvr_dev_id; return(0); out_fail: return(-1); } +/** + * @brief Reads an input channel from the appropriate driver + * @param[in] rcvr_id driver to read from + * @param[in] channel channel to read + * @returns Unitless input value + * @retval PIOS_RCVR_TIMEOUT indicates a failsafe or timeout from that channel + * @retval PIOS_RCVR_INVALID invalid channel for this driver (usually out of range supported) + * @retval PIOS_RCVR_NODRIVER driver was not initialized + */ int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel) { - struct pios_rcvr_dev * rcvr_dev = &pios_rcvr_devs[rcvr_id]; + // Publicly facing API uses channel 1 for first channel + if(channel == 0) + return PIOS_RCVR_INVALID; + else + channel--; + + if (rcvr_id == 0) + return PIOS_RCVR_NODRIVER; + + struct pios_rcvr_dev * rcvr_dev = PIOS_RCVR_find_dev(rcvr_id); if (!PIOS_RCVR_validate(rcvr_dev)) { /* Undefined RCVR port for this board (see pios_board.c) */ - PIOS_DEBUG_Assert(0); + PIOS_Assert(0); } PIOS_DEBUG_Assert(rcvr_dev->driver->read); From 032fa759ac85086c236fb19bb935063397affb0b Mon Sep 17 00:00:00 2001 From: zedamota Date: Wed, 12 Oct 2011 16:43:14 +0100 Subject: [PATCH 14/18] Fixes the zero while arming checkbox and and OP-575 --- .../src/plugins/config/configtaskwidget.cpp | 12 ++++++++++++ .../src/plugins/uploader/uploadergadgetwidget.cpp | 10 ++++++++-- .../src/plugins/uploader/uploadergadgetwidget.h | 1 + 3 files changed, 21 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp index 1bf45bd60..c7a082507 100644 --- a/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp @@ -197,6 +197,10 @@ void ConfigTaskWidget::populateWidgets() { cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale); } + else if(QCheckBox * cb=qobject_cast(ow->widget)) + { + cb->setChecked(ow->field->getValue(ow->index).toBool()); + } } setDirty(dirtyBack); } @@ -226,6 +230,10 @@ void ConfigTaskWidget::refreshWidgetsValues() { cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale); } + else if(QCheckBox * cb=qobject_cast(ow->widget)) + { + cb->setChecked(ow->field->getValue(ow->index).toBool()); + } } setDirty(dirtyBack); } @@ -254,6 +262,10 @@ void ConfigTaskWidget::updateObjectsFromWidgets() { ow->field->setValue(cb->value()* ow->scale,ow->index); } + else if(QCheckBox * cb=qobject_cast(ow->widget)) + { + ow->field->setValue((cb->isChecked()?"TRUE":"FALSE"),ow->index); + } } } diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp index 883955a5b..0f3affaa2 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp @@ -48,7 +48,8 @@ UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent) connect(m_config->resetButton, SIGNAL(clicked()), this, SLOT(systemReset())); connect(m_config->bootButton, SIGNAL(clicked()), this, SLOT(systemBoot())); connect(m_config->rescueButton, SIGNAL(clicked()), this, SLOT(systemRescue())); - + Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); + connect(cm,SIGNAL(deviceConnected(QIODevice*)),this,SLOT(onPhisicalHWConnect())); getSerialPorts(); QIcon rbi; @@ -105,7 +106,12 @@ QString UploaderGadgetWidget::getPortDevice(const QString &friendName) } return ""; } - +void UploaderGadgetWidget::onPhisicalHWConnect() +{ + m_config->bootButton->setEnabled(false); + m_config->rescueButton->setEnabled(false); + m_config->telemetryLink->setEnabled(false); +} /** Enables widget buttons if autopilot connected diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h index 075dc18a0..74a48425b 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h @@ -85,6 +85,7 @@ private: QLineEdit* openFileNameLE; QEventLoop m_eventloop; private slots: + void onPhisicalHWConnect(); void error(QString errorString,int errorNumber); void info(QString infoString,int infoNumber); void goToBootloader(UAVObject* = NULL, bool = false); From 1d5364878aaf4ae356a82b5f0ded9679aed8448b Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 13 Oct 2011 23:16:09 -0500 Subject: [PATCH 15/18] Update CameraStab icon with Muralha's new one --- .../src/plugins/config/images/camera.png | Bin 2854 -> 8558 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/camera.png b/ground/openpilotgcs/src/plugins/config/images/camera.png index 50ee4790404dbe833a968246a4e72ad4638a115f..b412c28d64206a48ae8159cf501a2f821ee660c5 100644 GIT binary patch literal 8558 zcmd^lXH-+&)-Gbf7X*%gA|gc*6@`Q<5V|xGsZtaONC`zCK@tcpU<0I!sF7YGB1jPs zkZu8m&=L@klF%Wcg%VmI>>JN{-}Bu&?s>oO&;57z7#Ue>?)f}(&b8*so@39%n421M zbDrj8V`Jksx~^x*#&&@I`*ZXlOR{$q{E77?gwnr_x`l8@p`HCUT}?b zwEE_A;$ChV=WLZsWKH~ZVV+*sL;PX4LQJh(L%dy8-Og!gimL}fSOmT>l(Tq{uMZpv z3DP+CPhJRX{96n@C;m?rl()vYe>rvA#9Uk#;SUp60?Ep_%3hTdzp4n5Q+Svm1PuX8MG{%-CNOFe@>ZLww==R8p;KL{9%Mx#M!1rWmD z11zVistT5s2g}RLury?l!ElswkPI9t@fU+04C(6c<%jY@z{P(vI=dhOP#Wi0p8hKY zU%!9T!jXS26Klc1LC$_)Igsq{kp5CMG5POReSQC}jYL_({>$J0NQ|@!_Je^fVMs)P zzbk9w+$DaS@`LF5!<X_e7u&NKb^Hxb7__kes-Qv#S^Ux8$D)6BCFL z9Eoyln`WmT1x4RmyM3=|CHm2^~<75>8N zAzTA|VQ|!6ShxSe>i;eFcQW|;u`KJs{JjEUZU+7cU-5qi4e|PWU#|Tv-=A2wzxPG= zZ?RyOGvMD_`@e1VUm{li{2u;0aaogpr#=kM%6ETOVoQIc<+9EToB2&EeW0!(F){Ju z#LKT=zrG!LSW!_SEG*p8((Z-T5_cVQo!C=g9PGn?c08}dA<^^0) z*xcMKCdI6*tW2!;udlCf?5>c>+63mfA#hC1t2>2@86%E zp5ETxwzRZdTwKIpFnW4=FMoP*ad9m#FVD}UyAfRiZ_Va83ke1ch*a)1JBCite+__Ud@p^4-E$3J8^FCN|a&mrtKA?BQ+S(eB zS9No9b9Q$A{P}ZfX{m;WMrUW|`1m-3x&83rL%`m7czBpXp#a<4qpRIOWQ>%Q6bJ;O z?NE32Hi3lXrR~|Os;aNEg#ZE-j=$dB-A&mbD=8^Kp-`Zxgh(U;kD`A5{23e^+%TOR z6BE<7^qF-qjg5_go3~bX7Jdn~(>hloDJiL=qXPs4^YQVe4)}eilmc%H zY1@>CohC6ow}DrwQQcOh4iMlamwB*$sUD3IISzyDo6u6o^d(ZaV^g0YFs^pk)A9*cuud0wR*^ z?Chzjsd;&MlarI7?Rxvb{@(uX_TENB$Bn(cz0KXVsi`R@lUXzxJw^W&hS%TU-{0D! z_bxR*=rG>eTYpb_`nbz{iaxlwHNCsfz~OMeXl*r6JK@fX1E9?(N99E}2KE8pgdUcY_~sAvJ?ali=%ghT*+KZ%Qt!1uNvl(MHi zHozQZY^@iVnl2klWQF6E?83)-+OVN4O>eQL|36=Bx3)MWSBb6x`e;Y#^*VXr&)yaa;- zV78c{dBqC$7BN_1YFgkcSbzddW^x}G_`flegbMDc?V#Dj9o^_;M z+f!;UdjT8eDB*aHgtp;>L^hEF5O&m||6B0i-uxGw<3A(+5AOfb&QZd{zjxv#@ z`RI7FD4+7dS(^;_t(?Kpfu$RDQ>eHk#|Znfjt7A%q(?aZnvFVvu&6#6MaB!sj>S^y z<4PIXx(?q)%}eA+eROllh($wO!ZNiwaT4l=0<*Ml8m@xQ)NPG~U{=G=c-Tv$OfJUH zhNkRUfH`uFq;A<1;><(bxcS;{VAO-Q7*US*8hQ@nCqq|g1( z<>_;b-Kc%(?ka7QYAM9_lYQF^@8n@Bm3Q}1xWJsD39M;G^BHDU{1xN`*M49SK$zPLjNUlSCr!r;jVBjT8`L!F1{uwNck`WeI-U{ zITI|RvkGUYa}}*5cT|K;S+iEe5MhY=0uOAEMV^Xo4J~Mj)?9m`o1B~#@eh8o(cnP` z#o!-_A`z(#Ap_OICs&j9A8|HRZ0^>tM*Ivi&zZ@}}vp(h6aM4Jh zx9`D0V5GVo@m_hav7>p8gNf|lTe!R>CZ^%89M~P2j!`5S|2U1LBTSl1ooN**g7gHv z=FX|C@QJmGNQ1Potg{yFz2A;t9v}y=bZzM%yH_9X_bPIPkoBCy6KU_D(KA zHoYOI62fb*$!P^X*IgH~k#PvV;>1611I+w5#jxl$Dehl9ctskGOG7^|&M_o^LW~;SSS7ft{f(f!j>(O7voyf^ z{}NpR*B{|=AiFTZ+yRw9z4202(=Tzl)cmUtwyQz8f<_;STl$siH4Pd4rg2_&ATl&?RoD9nqz-*XAn-d*yREg*_jFf!|Sn| zXYzQl6r3?wL4BNqx*+HAHuT)(k?4w$j|suowPGeXxhv#oh<*FLe&EY&SiBnF7MWLhgrR!_O~I4x|M z{XE{NHm32RoKFoUb-Tx`H@9>{v#q3td3J809;G){(*1n$gRA>ZDPvS-^zAYlB{&|I zhXi%?_y*`+{61*6?y;=-=Eeyq?d(8Rl|sH_+RPfG+WqQ4dR+MX5H#>yi;k77riAd8 zgNiZ_X;AdBgPEBt5`xqxjvFO)Uv5Isv(8t)Q+h2kwTQKL8_6Ip>>$L$KxY-{8 z0dKU{<`|S1@lY8G%#(z+mg-t?KsyFlWoM$?Sq9?&Tx!j2}mSinR z$=2NPY(vr3J=#o}D!?}||F9HfB{L4U|NQBg5%x_KmDx_dPae1R9+^ig;`#@q=`_<7 zwa{~J^>1!nr80>ZAk716_kK9qs1?|S^@uWs!iA|!7fDiu5zPf&uzp1A&iXKS;-I5l zk0?~cC}JN}+9olFy$-p6*glKV8go*2n1_zicBBbv?}fRzC%!Tsj7otnoJB)@n%*Ee zQ?mAv*TNibcb%nJenF#vBWRxbhK@5((&Y~>vXN%J8{ftbA%@d%CN>|;gl4u$KRY|) z`QohQFWDH!$S5fE-#?EFQ=31J%i$%_4oX2Fojh^NB!EBs5H$WM@OktYs zm}Ciizdq^I-h+ql`Do1T*^J?&Xc?7MJ6VH^A?|xlnGFY~FW2+h3qaIdmji&jZ2T$a z{i;B%g|eNa<|&WSw#p%2OVNq-o`HOOxT$=Rcw(9PoY9Vby%;|F<6Bii4H2}R3|C(F zP4s=TW$G5|s1#4Wpb+B+pQq1VVLveFHwFj9R z6&%ZQ9%hT(NNFOtH}s5Ikm&2Gb{|y!C~{dw(c`}Ig77O!Jypg%&HSjlZ>+FL>kheg zS-;YWB9_tTF`%G#v2F^q6DOJkDW$&m$Qa!4uhFbk9XXZvp1b;h0#jd%cjhh5Ebt%A zx=r#OLxE16|A1oTJ3d%zE3;v+kGFMds&^A-7716dQWV=Z?E=jQeLXeHLMBd~afwlk z`u9V*W`%DD?jEd*)~x+#U^Wb>JgtA`jYUJ8Qt>>@cP{&^qT5JPdq^oEsj6|tv$D}J zPff6{VT(r%RmHo>4RBchI28e#nS;53{LU*#lo7VSWMdL=K>K~@81Q;wS}1Ca+F}cd z)aM}{$#V2I2zK$L$G5F~s0&_pp75%~#qlA1cEWJzQ&hXQ_V;2z5i~}6YA)D82N{@Q zK^f>2l^Sw(JgNHR{6`~)XFcG$yl$bx}~0ZN*P$=bq#YE_z9L&%{D_d_vz6|RyFiN;l}Cy#frCX zVOB?2g~&^*?8Fjq$g0_Wn2AZj@j^yk!D=+wG}xu1-0MJ8R&br|9i+dCzS$;bYDd=z z=Rh$l=Db9I&fO(}uHYD=-$JyCF%BPQ+NnMulpv?@dqxG9NH^-_MssbOa&y3ch||dm z_`R-ex4t|vu=%U%o1CXm-W|{6Ii)TuO4Zr@D9Kr)Cyt<0;tIK;v#XT|u7or-d~(Y> z0!2tJx)Fd++aU8I@<&O{`D@t=AAX+wlp^?TWi;Es!_MJq$p^O!H9j*-yIO7zg+jz0 zb8_7H@!6V9bFi(iMa5RkC&_ZL_^rL3VS%)NK$nv0ug_@l!bs-AQ>&+Whsn3);7d$Y zLqP;rGX%e+v|xf}18G456Hp|;7Sx`v*yRH)ljGei)yxfT9E-kxs7>(mWZ-qEzk zQ@k?Bt~*pSq3n9c=VdLnWenUr;UmRvSKhjgY< zHVcqJFA53K<{8Y+(eIickdwldSnTRua9BzK6?zTn>0`=Z|SG}#-LVf`<*nBqb4xyiP zlyh@EVR@KWu&QSay*SY;6|tq6lJj1{dAH30hv;P&Ir?@bs~wc^@KQ>SQ{MhN(W{i! zVYye&lnWac2AYPO-<(0_Wal=iUgAeB+&($`{G+ygi=o|3R!#G0-#&{t=iNmO$eHn^ zt$@=HWWK)ApXo|JJRB_lMPLlF`Czsr#pFTO{*wyY^+U~+{NeQ7up$ImH}o-BK#Vzl z3-3_qwU@W`^V1u1_#Nh(;H_7axa>1IihX^x`d}ie`2r!U)*(c4XR|Rj(y-Y<2N8YN zosw2s=|~@ZJMFdq&hm+2bJFJL%LnPlO!%3~$KcIr7gfS4uHfj*x1Q{k)wo(c@J>vGgXH$KSth8ySeftUCI9E!z;$%UfO`O1}EDR5q zUIdms!QqD<019vrRfL- z2T!^b=|yWCc1N$~Id(iKF!bw^goi;Nxh)M$-^AaDo=*tN12bP(WY^n^sqctM#>6+> zm)vl?ji*e93B5HtbXijHD_KUK0fPm1Saa0s^(39Y#Hvyh(lSi4FUm5`A8s5Mz*1)3 z92zP4%-PS=r6}b+#VD2#lQVInrdD*P^dwhGG9G-B(;5cQlIF zN$iMu%jo~qo6Z+|kUTy5Np^E&`=qHkQ2#N^nJ8w%D*T>0@|hMZ_Bji_^K=QTx_z78 z;{`S?h|9V$N;0cd#yY}&+Kh8C?V5<~5O@j?#a_tTUmJ1Fj_+v5V!tn!YvsUUiph1( zaJb(N+3INR5^2;0l#bc?%Z9=PZXH_7z5Jq@LzP}2Hqw>=KV||Mppzs?aD50r6!Nwk zqcBWPUD8(OU<4}UMDU>2q11WH>ZIU3Q!SrqblnHaT&<{?a&?H4_+^Ir5e1K5Ik-$y zZf2gmT!p=41SK;1*kUr*@oK}wRsqjg3~lJhX5$urHI4bMqW0&y^y{- zb#<>2h7(;Ls%M#&W_U}+#ERzntO7p;x;?t3`wwJhsPdneW_0f38FW@9o74;A=j`c1 z-Jfe?E-!@8C9tY`7d^hsuZ%iM;RPz4)tYmBw0bjjQU2sz9HTo_>n{Jv#(CF#^sEsN z(HO~XKfx!p%qh6Td6*f%L)>ue_{xe*x>m| zRKh}bFUpEuKOqK{8Owe*%@0+WZXch$0&9^AAGnOBD7-w2b?sBpuem915pGuhsODaF zk&nUw1{7Zzy6EH|yS(PGTQAk~YUK0Y4s|q_zmZn67Hiu564&&|y3g)PoV4O$h7kVc znYbHQl-|VmKR%VB+20UQ?8Zs=5TNfD1nFaEz1{E?6z*T%X-DEW(`I?0nd%Cd3pJF1 z^3&QHkIF-kMYb zZR7k>W9E>AsH&drTodoqDN;Vn`qsBylK(=X3~$Hqq5?1D?%_tp`5%;l5r?0*_IBB; zH7D1?hdM6|AfJ-&+<60!h;l`>KOfKg*`Fe_Q(fob(}GmLp~nvP2LW16dqKbKXE0Mi&^|gGe={PQrdOz zM=QC4I@U5!3rFgfSs(e%D8`AcuLX|HfCDLowV>b}SJwChuBx|GF+99vz z)~wEm*qjKoB7Sw;=A@{=$S-VYcy}~Yo!RG;?q)#03=_gJk8M$&Z#uGojq+v%h%Md>i}AF%@r`C&2V))XKANS zOss~oCV9AV(*Hs3;2XbC&p_N{vcz*~gEMEEDSFKCvnvFV!BF>}oFVdj-9hNBSx}oY zrEOdPqC381Px>Fk%$4Aom|QflvvnWOUe)B~TE>%^p5mdj@=nD7xS>-6oPI|MK)SBU z2nkh_RcET>j~P1`PW<>L2a)3s@w|&e3WgJ7M0A;UbT+#7HQS4=jDD*mc7L|q_ahHR zc6ZCCA}&2UcoeFMC@4=BCy*>#8q1+THH1{dF2Zp(RdQs6@06c`DCoJn3C zhbz3X#Gouy&gK@v=L5@1qNVn7i_N7b^Ih_8+JBV1U8=7mU;lc#@F~fhjKw6>3iJqMnO>r@%-SJfs-snH@tQVnX7~d_?7c`f= zj^lm8=7zt)VQ&whUeF%p(IUR8LGWlD;!LGsLmrFg1ayD&3QJ-^eV@#&HeQ_53x^q1alOR zP9_vIOvJHnCKDv8x7}DMak_`iwmWNZiq2eLY&tSie~DsPup6I9Mq3cxzlAQ&zGs=f z&skgal&c39rtCD=xr!^X%?VQ$s>78xxe4LXmAM^jMc^p9;SO9LWq7bORJSJh1?^g% z8e*Mf-jvSWm^-45M>`W6$7Um1hEAR$b@+;^-Yu|?vBq%28xAwx1|?E7*PCcD8T%e9R%vc13Kkxe|yzlcl&vQP{c0SKJ-*e7$lFZEvIaq~Q0RZ4IHqy5MdDOq1 znF$$^dLx~9tHfG`&B~-09Z?n^>r+9d9?f|4^R^f{hcjzY18zT3g6Mm$gz_-@bFM$db)xQY* zuy6|k;_DS5G6^i&H<7>x7Y1`q-l%|VAfpFbgpdZ7|94xGANTIq*-b0t4mG1;zgbzL z_b}JtZZYfm3Cz%ODo)MJAoxHu{Q*YK_b;#%GX)1Y|HZw--tK`Sj zC@<|Ertp7IhdlK54#jBklzz6B%j)z;^q;%*OuJy!>6)~~@^cSC3Wbs?#gZna12-^A zgW63lfPG z&o}Gbru(W0Ylw1v!K!X-ZeB_KOU*~cPI5bMP@7y*{Y%<_ltmT1VQTBd3CG!L&$)v` zfD|L%wYpneRmH-e?2$7n^ohVTH;{fgvDY;_Cntwa#? zFh^!Inmb896)8P98>ohuZ1TR)*4DOtv{_eL?&;q#JMSl;r>7@?K**&RzsgTZ;iTmA z^CZ2a_RMdGQCP(XmF^fC4hn_xCo|5>%;0{W(&u+@S-ug6c+u72e7z@6w0M&Ar&MmK ztIzqVf$N!le>1p~ZN9XJa+SzD3`X?3fXCGQ<^W8cqeH!Ka!F!zH00!9k=Taf?Dv1* z<)xz+dsE>hD?>JkBXz*tkN(v`hEOsFw)y0%Z@czs(^uX;t{EfTj@Wk|%#uG?O1}q7 z(g!qdiJTs;7J{I6JHJ}EnZ<_UI1kDm8M!|*%*7O|7QA7J4vD-*qtVm?SJ-DGk9{2; z%klRd9N^GoIYtU|kqj%SmxOT|rp2X)Deq<=)8=^Xb*Xg9`a3%H3GwupzPTZ$fr~;) zyBU>V=)J-4^x3oZ;a1S3Ynz*~6W&|3tjfyDYc!fcDBa2J0i#Xww9HFaR>;DRnzXcZ zW5YD9FO>S&(2~AYQ5Z=W%2oCDFiulcQSo#xiPL!lq)E-s_axZbz@Ug*A?(HG@4GCQ zw>5~RhQyMxGJ_hE3JUJ~Qc`r)N&*hzTAxiC30?b3!spBDkuLqf#US;ay$Pqyw#3qr zN(C)1n7p>ai=M@PV$=8EmAzj@(6Q%uhwd2~CXjB66E2G04tIAhS=DOMbI4` z9Wdzkc7^cp@E|u1&~+N*gtH%D6Zynn46X}B)^+ULj@9j5NFH3)y?2j@!NB7tn}K=; z_&5CAR4Wzv=J;#7U#q=s4$F27oNbPNywfNANFaNqmm3OkaB#4_nLYrUx~lyW)Nnm~ zwApvs^TRc|$gPmI4^koAyt3Ns^POZerAW$Tv9@J)l*2e3CnRnWH85aIYwDTrDmTq# zN0M>4f{B6LAy1vprQu2Nq67O@5F*NqFA5nE(Y|ksM$b6&v%qAvcf@32%mUf&>lw3o z4XMJI8Ww*B(04X(*fc%NjP}Yh3nZU0T^S`o6M2h%z`U~T{#c0-fjFjSN^3uU+(FVy zY>bvzfXet@va7|!rpbx*T3m;$6gT!dX$U>IGrHc0B?x)N+90D?QR-fCjV87W(77;2 z)#S^WcLlRO*A*fBIy+(mTMQX1mupS+-Te_SY1L z7G(KCo0VCf#v4I^)4Jv1{97KVhM}%9lNXH>G2$@g=Vei{P;)e2#l1omg^w2xPU%$t z&2jl!N=m36A6BxsT@4I@yjT4S%BxXRI8;t^oc1ZN-1%HHo0# zfcVebzrk_$^z_(Ht?qVXTmIt_0IvBpYNz2!=h;!s*H?EhHpne54W!%VEWRd?tQ#y7 z`2m^E;)VCmC2>bTs&u?oRwwJ-K37Wse@#vr{UDUSW19<759X)@ZSYC!XWnZUG;jch z>@_vD%FM8W%aN@D3yeV2_&CNv>}YRuVrNK|Dv({7C#;Ii@Bp*DB=(>Mj$$^qj<3aK zY;R4G57sLR*^zq}S{_mRel2_)kJqdlQ&v^wjaavODhmaG_L-C>?}?3#qobp3F#idv z@9zH@$96Cm%cZESTsFox4p%u>&JEx~(B_{@L=lL0-LdC`(~Ya6tE<)g7oePCnt!xY zCa^7~O-)VJHd!%MP@q7b%_`i(Z+FFXYr2KYs?M?YZoH9H3{mrlxxy@ebgbQ8;mwax zlVr!Napw2f;*UBg6t9npa9>|vV@Ie-EgdWFX56vT1DMr|R9#?|+?122FA`tU`*1B~R;#C61ay_r|6{0_f+uyb*JQm-PD zNSyNW^7<*?hx!TJMO{CB+$b5TBq=)*dgird;JSKx=PlxA75ov)yQr2VNY^5EhKkC0>);L zwY;^owDcs32jXt?mSs*X{$;f|rY3k?Sc#QQWm}{3qA1X0E@gZqnQwLva!EvIadDAK zC{fcmp1_DA`nw-CSv2kP89Xo0e0=0l{0Fc2b0egOQjVx`+Qnrjk8BZx`vL1gM}=U) zqFYSb+SvhKh3{=dP1DX^h%-;i@tYVv%Q;dJRJTOO$q Date: Wed, 19 Oct 2011 13:37:35 +0200 Subject: [PATCH 16/18] PiOS.posix: bugfix in pios_udp com driver - data send loop --- flight/PiOS.posix/posix/pios_udp.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/PiOS.posix/posix/pios_udp.c b/flight/PiOS.posix/posix/pios_udp.c index f7f91f620..5ccbae767 100644 --- a/flight/PiOS.posix/posix/pios_udp.c +++ b/flight/PiOS.posix/posix/pios_udp.c @@ -194,7 +194,7 @@ static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail) length = (udp_dev->tx_out_cb)(udp_dev->tx_out_context, udp_dev->tx_buffer, PIOS_UDP_RX_BUFFER_SIZE, NULL, &tx_need_yield); rem = length; while (rem>0) { - len = sendto(udp_dev->socket, udp_dev->tx_buffer, length, 0, + len = sendto(udp_dev->socket, udp_dev->tx_buffer+length-rem, rem, 0, (struct sockaddr *) &udp_dev->client, sizeof(udp_dev->client)); if (len<=0) { From b00751af915c42421b2d1e7c141a890b158ba6f0 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Wed, 19 Oct 2011 15:50:42 +0200 Subject: [PATCH 17/18] Systemmod bugfix: UAVObject used without Initialization --- flight/Modules/System/systemmod.c | 1 + 1 file changed, 1 insertion(+) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 168b46aa6..c95dab409 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -114,6 +114,7 @@ int32_t SystemModInitialize(void) // Must registers objects here for system thread because ObjectManager started in OpenPilotInit SystemSettingsInitialize(); SystemStatsInitialize(); + FlightStatusInitialize(); ObjectPersistenceInitialize(); #if defined(DIAGNOSTICS) TaskInfoInitialize(); From cb8d9c791cb70cf404b2c472ce5d491ccebf1f6a Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Wed, 19 Oct 2011 20:46:14 +0200 Subject: [PATCH 18/18] PiOS.posix: fixed missing defines in pios_config. removed platform specific inclde from Systemmod (pios_config.h gets included from pios.h) --- flight/Modules/System/systemmod.c | 1 - flight/OpenPilot/System/inc/pios_config_posix.h | 8 ++++++++ 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index c95dab409..dc004d592 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -48,7 +48,6 @@ #include "taskinfo.h" #include "watchdogstatus.h" #include "taskmonitor.h" -#include "pios_config.h" // Private constants diff --git a/flight/OpenPilot/System/inc/pios_config_posix.h b/flight/OpenPilot/System/inc/pios_config_posix.h index e8701be90..89a1d967e 100644 --- a/flight/OpenPilot/System/inc/pios_config_posix.h +++ b/flight/OpenPilot/System/inc/pios_config_posix.h @@ -62,6 +62,14 @@ /* Stabilization options */ #define PIOS_QUATERNION_STABILIZATION +/* Alarm Thresholds */ +#define HEAP_LIMIT_WARNING 4000 +#define HEAP_LIMIT_CRITICAL 1000 +#define IRQSTACK_LIMIT_WARNING 150 +#define IRQSTACK_LIMIT_CRITICAL 80 +#define CPULOAD_LIMIT_WARNING 80 +#define CPULOAD_LIMIT_CRITICAL 95 + /* GPS options */ #define PIOS_GPS_SETS_HOMELOCATION