From 44c8c9fbe51a2e66d88f09bea21c68cb6b00a74b Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Fri, 18 Nov 2011 18:30:58 +0100 Subject: [PATCH 01/24] GCS/ScopePlugin: Allow SoftwareInterpolation of measurement value --- .../src/plugins/scope/plotdata.cpp | 21 +++++++++++++-- .../openpilotgcs/src/plugins/scope/plotdata.h | 3 +++ .../src/plugins/scope/scopegadget.cpp | 2 ++ .../scope/scopegadgetconfiguration.cpp | 3 +++ .../plugins/scope/scopegadgetconfiguration.h | 1 + .../plugins/scope/scopegadgetoptionspage.cpp | 23 +++++++++++----- .../plugins/scope/scopegadgetoptionspage.h | 4 +-- .../plugins/scope/scopegadgetoptionspage.ui | 26 +++++++++++++++++++ .../src/plugins/scope/scopegadgetwidget.cpp | 3 ++- .../src/plugins/scope/scopegadgetwidget.h | 2 +- 10 files changed, 76 insertions(+), 12 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/scope/plotdata.cpp b/ground/openpilotgcs/src/plugins/scope/plotdata.cpp index f2d4bb5af..fdcb75a83 100644 --- a/ground/openpilotgcs/src/plugins/scope/plotdata.cpp +++ b/ground/openpilotgcs/src/plugins/scope/plotdata.cpp @@ -49,9 +49,12 @@ PlotData::PlotData(QString p_uavObject, QString p_uavField) xData = new QVector(); yData = new QVector(); + yDataHistory = new QVector(); curve = 0; scalePower = 0; + interpolationSamples = 1; + interpolationSum = 0.0f; yMinimum = 0; yMaximum = 0; @@ -78,6 +81,7 @@ PlotData::~PlotData() { delete xData; delete yData; + delete yDataHistory; } @@ -91,7 +95,13 @@ bool SequencialPlotData::append(UAVObject* obj) if (field) { //Shift data forward and put the new value at the front - yData->append( valueAsDouble(obj, field) * pow(10, scalePower)); + yDataHistory->append( valueAsDouble(obj, field) * pow(10, scalePower)); + interpolationSum += valueAsDouble(obj, field) * pow(10, scalePower); + if(yDataHistory->size() > interpolationSamples) { + interpolationSum -= yDataHistory->first(); + yDataHistory->pop_front(); + } + yData->append(interpolationSum/yDataHistory->size()); if (yData->size() > m_xWindowSize) { yData->pop_front(); } else @@ -117,8 +127,15 @@ bool ChronoPlotData::append(UAVObject* obj) //Put the new value at the front QDateTime NOW = QDateTime::currentDateTime(); + yDataHistory->append( valueAsDouble(obj, field) * pow(10, scalePower)); + interpolationSum += valueAsDouble(obj, field) * pow(10, scalePower); + if(yDataHistory->size() > interpolationSamples) { + interpolationSum -= yDataHistory->first(); + yDataHistory->pop_front(); + } + double valueX = NOW.toTime_t() + NOW.time().msec() / 1000.0; - double valueY = valueAsDouble(obj, field) * pow(10, scalePower); + double valueY = interpolationSum/yDataHistory->size(); xData->append(valueX); yData->append(valueY); diff --git a/ground/openpilotgcs/src/plugins/scope/plotdata.h b/ground/openpilotgcs/src/plugins/scope/plotdata.h index 2d61f12c6..0b87c9937 100644 --- a/ground/openpilotgcs/src/plugins/scope/plotdata.h +++ b/ground/openpilotgcs/src/plugins/scope/plotdata.h @@ -72,12 +72,15 @@ public: QString uavSubField; bool haveSubField; int scalePower; //This is the power to which each value must be raised + int interpolationSamples; + double interpolationSum; double yMinimum; double yMaximum; double m_xWindowSize; QwtPlotCurve* curve; QVector* xData; QVector* yData; + QVector* yDataHistory; virtual bool append(UAVObject* obj) = 0; virtual PlotType plotType() = 0; diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp index ccf4a8b82..b4b1f24fa 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadget.cpp @@ -61,12 +61,14 @@ void ScopeGadget::loadConfiguration(IUAVGadgetConfiguration* config) QString uavObject = plotCurveConfig->uavObject; QString uavField = plotCurveConfig->uavField; int scale = plotCurveConfig->yScalePower; + int interpolation = plotCurveConfig->yInterpolationSamples; QRgb color = plotCurveConfig->color; widget->addCurvePlot( uavObject, uavField, scale, + interpolation, QPen( QBrush(QColor(color),Qt::SolidPattern), // (qreal)2, (qreal)1, diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp index 63a48e495..6337be38f 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.cpp @@ -65,6 +65,7 @@ ScopeGadgetConfiguration::ScopeGadgetConfiguration(QString classId, QSettings* q color = qSettings->value("color").value(); plotCurveConf->color = color; plotCurveConf->yScalePower = qSettings->value("yScalePower").toInt(); + plotCurveConf->yInterpolationSamples = qSettings->value("yInterpolationSamples").toInt(); plotCurveConf->yMinimum = qSettings->value("yMinimum").toDouble(); plotCurveConf->yMaximum = qSettings->value("yMaximum").toDouble(); @@ -118,6 +119,7 @@ IUAVGadgetConfiguration *ScopeGadgetConfiguration::clone() newPlotCurveConf->uavField = currentPlotCurveConf->uavField; newPlotCurveConf->color = currentPlotCurveConf->color; newPlotCurveConf->yScalePower = currentPlotCurveConf->yScalePower; + newPlotCurveConf->yInterpolationSamples = currentPlotCurveConf->yInterpolationSamples; newPlotCurveConf->yMinimum = currentPlotCurveConf->yMinimum; newPlotCurveConf->yMaximum = currentPlotCurveConf->yMaximum; @@ -157,6 +159,7 @@ void ScopeGadgetConfiguration::saveConfig(QSettings* qSettings) const { qSettings->setValue("uavField", plotCurveConf->uavField); qSettings->setValue("color", plotCurveConf->color); qSettings->setValue("yScalePower", plotCurveConf->yScalePower); + qSettings->setValue("yInterpolationSamples", plotCurveConf->yInterpolationSamples); qSettings->setValue("yMinimum", plotCurveConf->yMinimum); qSettings->setValue("yMaximum", plotCurveConf->yMaximum); diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h index 1aadcaf5b..570ebe1f9 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetconfiguration.h @@ -41,6 +41,7 @@ struct PlotCurveConfiguration QString uavField; int yScalePower; //This is the power to which each value must be raised QRgb color; + int yInterpolationSamples; double yMinimum; double yMaximum; }; diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp index e44ccb08f..d0d364b68 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp @@ -101,9 +101,10 @@ QWidget* ScopeGadgetOptionsPage::createPage(QWidget *parent) QString uavObject = plotData->uavObject; QString uavField = plotData->uavField; int scale = plotData->yScalePower; + int interpolation = plotData->yInterpolationSamples; QVariant varColor = plotData->color; - addPlotCurveConfig(uavObject,uavField,scale,varColor); + addPlotCurveConfig(uavObject,uavField,scale,interpolation,varColor); } if(m_config->plotCurveConfigs().count() > 0) @@ -163,6 +164,10 @@ void ScopeGadgetOptionsPage::setYAxisWidgetFromPlotCurve() int rgb = varColor.toInt(&parseOK); setButtonColor(QColor((QRgb)rgb)); + + int interpolation = listItem->data(Qt::UserRole + 4).toInt(&parseOK); + if(!parseOK) interpolation = 1; + options_page->spnInterpolationSamples->setValue(interpolation); } void ScopeGadgetOptionsPage::setButtonColor(const QColor &color) @@ -235,6 +240,10 @@ void ScopeGadgetOptionsPage::apply() newPlotCurveConfigs->color = QColor(Qt::black).rgb(); else newPlotCurveConfigs->color = (QRgb)rgb; + + newPlotCurveConfigs->yInterpolationSamples = listItem->data(Qt::UserRole + 4).toInt(&parseOK); + if(!parseOK) + newPlotCurveConfigs->yInterpolationSamples = 1; plotCurveConfigs.append(newPlotCurveConfigs); } @@ -261,6 +270,7 @@ void ScopeGadgetOptionsPage::on_btnAddCurve_clicked() if(!parseOK) scale = 0; + int interpolation = options_page->spnInterpolationSamples->value(); QVariant varColor = (int)QColor(options_page->btnColor->text()).rgb(); @@ -270,27 +280,27 @@ void ScopeGadgetOptionsPage::on_btnAddCurve_clicked() options_page->lstCurves->currentItem()->text() == uavObject + "." + uavField) { QListWidgetItem *listWidgetItem = options_page->lstCurves->currentItem(); - setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,varColor); + setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,interpolation,varColor); }else { - addPlotCurveConfig(uavObject,uavField,scale,varColor); + addPlotCurveConfig(uavObject,uavField,scale,interpolation,varColor); options_page->lstCurves->setCurrentRow(options_page->lstCurves->count() - 1); } } -void ScopeGadgetOptionsPage::addPlotCurveConfig(QString uavObject, QString uavField, int scale, QVariant varColor) +void ScopeGadgetOptionsPage::addPlotCurveConfig(QString uavObject, QString uavField, int scale, int interpolation, QVariant varColor) { //Add a new curve config to the list QString listItemDisplayText = uavObject + "." + uavField; options_page->lstCurves->addItem(listItemDisplayText); QListWidgetItem *listWidgetItem = options_page->lstCurves->item(options_page->lstCurves->count() - 1); - setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,varColor); + setCurvePlotProperties(listWidgetItem,uavObject,uavField,scale,interpolation,varColor); } -void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetItem,QString uavObject, QString uavField, int scale, QVariant varColor) +void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetItem,QString uavObject, QString uavField, int scale, int interpolation, QVariant varColor) { bool parseOK = false; @@ -306,6 +316,7 @@ void ScopeGadgetOptionsPage::setCurvePlotProperties(QListWidgetItem *listWidgetI listWidgetItem->setData(Qt::UserRole + 1,QVariant(uavField)); listWidgetItem->setData(Qt::UserRole + 2,QVariant(scale)); listWidgetItem->setData(Qt::UserRole + 3,varColor); + listWidgetItem->setData(Qt::UserRole + 4,QVariant(interpolation)); } /*! diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h index cbbf9201b..39c0b3ea5 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.h @@ -66,8 +66,8 @@ private: Ui::ScopeGadgetOptionsPage *options_page; ScopeGadgetConfiguration *m_config; - void addPlotCurveConfig(QString uavObject, QString uavField, int scale, QVariant varColor); - void setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, QVariant varColor); + void addPlotCurveConfig(QString uavObject, QString uavField, int scale, int interpolation, QVariant varColor); + void setCurvePlotProperties(QListWidgetItem *listWidgetItem, QString uavObject, QString uavField, int scale, int interpolation, QVariant varColor); void setYAxisWidgetFromPlotCurve(); void setButtonColor(const QColor &color); diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui index 2aaee1942..147f972f1 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui @@ -159,6 +159,32 @@ + + + + Smooth Interpolation: + + + + + + + samples + + + 1 + + + 1001 + + + 10 + + + 1 + + + diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp index dfbd9d614..2270178cd 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp @@ -356,7 +356,7 @@ void ScopeGadgetWidget::setupChronoPlot() // scaleWidget->setMinBorderDist(0, fmw); } -void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor, QPen pen) +void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor, int interpolationSamples, QPen pen) { PlotData* plotData; @@ -369,6 +369,7 @@ void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField plotData->m_xWindowSize = m_xWindowSize; plotData->scalePower = scaleOrderFactor; + plotData->interpolationSamples = interpolationSamples; //If the y-bounds are supplied, set them if (plotData->yMinimum != plotData->yMaximum) diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h index fd8aaf550..09e79d6b0 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h @@ -110,7 +110,7 @@ public: int refreshInterval(){return m_refreshInterval;} - void addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor = 0, QPen pen = QPen(Qt::black)); + void addCurvePlot(QString uavObject, QString uavFieldSubField, int scaleOrderFactor = 0, int interpolationSamples = 1, QPen pen = QPen(Qt::black)); //void removeCurvePlot(QString uavObject, QString uavField); void clearCurvePlots(); int csvLoggingStart(); From 30b6ae90f35aed3c93ef01860c049c1421b38145 Mon Sep 17 00:00:00 2001 From: LM Date: Mon, 14 Nov 2011 08:39:45 +0100 Subject: [PATCH 02/24] Added UAVObject sorting to make UAVObj structs align to word-boundaries. Else copying to / from UAVObjects will fail on Cortex M4 with an alignment error, since the proper alignment is not visible to the compiler in a line like this: float* data = UAVObj.Roll; data[2] = yaw; --- .gitignore | 2 ++ ground/uavobjgenerator/uavobjectparser.cpp | 8 ++++++++ 2 files changed, 10 insertions(+) diff --git a/.gitignore b/.gitignore index 6c4d8b39f..03797f84f 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,5 @@ +# Exclude temporary and system files +.DS_Store # /flight/ /flight/*.pnproj diff --git a/ground/uavobjgenerator/uavobjectparser.cpp b/ground/uavobjgenerator/uavobjectparser.cpp index cba02f8ee..414712658 100644 --- a/ground/uavobjgenerator/uavobjectparser.cpp +++ b/ground/uavobjgenerator/uavobjectparser.cpp @@ -111,6 +111,11 @@ int UAVObjectParser::getNumBytes(int objIndex) } } +bool fieldTypeLessThan(const FieldInfo* f1, const FieldInfo* f2) +{ + return f1->numBytes > f2->numBytes; +} + /** * Parse supplied XML file * @param xml The xml text @@ -200,6 +205,9 @@ QString UAVObjectParser::parseXML(QString& xml, QString& filename) // Get next element childNode = childNode.nextSibling(); } + + // Sort all fields according to size + qStableSort(info->fields.begin(), info->fields.end(), fieldTypeLessThan); // Make sure that required elements were found if ( !accessFound ) From 6913d14e8229f412058d3946efc74b2c4335356a Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Fri, 25 Nov 2011 15:11:58 +0100 Subject: [PATCH 03/24] GCS:Logging: Correctly adhere to replay speed, and check logfile for plausibility/corruption --- .../src/plugins/logging/logfile.cpp | 28 ++++++++++++++++--- .../src/plugins/logging/logfile.h | 4 +-- 2 files changed, 26 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/logging/logfile.cpp b/ground/openpilotgcs/src/plugins/logging/logfile.cpp index f02bce22a..7a74d6367 100644 --- a/ground/openpilotgcs/src/plugins/logging/logfile.cpp +++ b/ground/openpilotgcs/src/plugins/logging/logfile.cpp @@ -88,9 +88,12 @@ void LogFile::timerFired() if(file.bytesAvailable() > 4) { - // TODO: going back in time will be a problem - while ((myTime.elapsed() - timeOffset) * playbackSpeed > lastTimeStamp) { + int time; + time = myTime.elapsed(); + // TODO: going back in time will be a problem + while ((lastPlayed + ((time - timeOffset)* playbackSpeed) > lastTimeStamp)) { + lastPlayed += ((time - timeOffset)* playbackSpeed); if(file.bytesAvailable() < 4) { stopReplay(); return; @@ -98,6 +101,11 @@ void LogFile::timerFired() file.read((char *) &dataSize, sizeof(dataSize)); + if (dataSize<1 || dataSize>(1024*1024)) { + qDebug() << "Error: Logfile corrupted! Unlikely packet size: " << dataSize << "\n"; + stopReplay(); + return; + } if(file.bytesAvailable() < dataSize) { stopReplay(); return; @@ -113,7 +121,19 @@ void LogFile::timerFired() return; } + int save=lastTimeStamp; file.read((char *) &lastTimeStamp,sizeof(lastTimeStamp)); + // some validity checks + if (lastTimeStamp (60*60*1000)) { // gap of more than 60 minutes) + qDebug() << "Error: Logfile corrupted! Unlikely timestamp " << lastTimeStamp << " after "<< save << "\n"; + stopReplay(); + return; + } + + timeOffset = time; + time = myTime.elapsed(); + } } else { stopReplay(); @@ -125,6 +145,7 @@ bool LogFile::startReplay() { dataBuffer.clear(); myTime.restart(); timeOffset = 0; + lastPlayed = 0; playbackSpeed = 1; file.read((char *) &lastTimeStamp,sizeof(lastTimeStamp)); timer.setInterval(10); @@ -142,12 +163,11 @@ bool LogFile::stopReplay() { void LogFile::pauseReplay() { timer.stop(); - pausedTime = myTime.elapsed(); } void LogFile::resumeReplay() { - timeOffset += myTime.elapsed() - pausedTime; + timeOffset = myTime.elapsed(); timer.start(); } diff --git a/ground/openpilotgcs/src/plugins/logging/logfile.h b/ground/openpilotgcs/src/plugins/logging/logfile.h index 861249e4a..a07e1832a 100644 --- a/ground/openpilotgcs/src/plugins/logging/logfile.h +++ b/ground/openpilotgcs/src/plugins/logging/logfile.h @@ -27,7 +27,7 @@ public: bool stopReplay(); public slots: - void setReplaySpeed(double val) { playbackSpeed = pow(10,(val)/100); qDebug() << playbackSpeed; }; + void setReplaySpeed(double val) { playbackSpeed = val; qDebug() << playbackSpeed; }; void pauseReplay(); void resumeReplay(); @@ -45,11 +45,11 @@ protected: QTime myTime; QFile file; qint32 lastTimeStamp; + qint32 lastPlayed; QMutex mutex; int timeOffset; - int pausedTime; double playbackSpeed; }; From 3303313908dd24292e688c94eed68af3f62e4b6c Mon Sep 17 00:00:00 2001 From: naiiawah Date: Fri, 25 Nov 2011 16:12:38 -0700 Subject: [PATCH 04/24] Fixes for OP-595: Changed the UAV import of saved settings to not pull in invalid enum values. Will warn on the dialog that an element of the UAVObject was invalid and turn off the "save" checkbox. Also will send a qDebug output showing the UAVObject name and the invalid enum value. --- .../src/plugins/uavobjects/uavobjectfield.cpp | 12 ++++++++---- .../src/plugins/uavobjects/uavobjectfield.h | 2 +- .../uavsettingsimportexportfactory.cpp | 16 ++++++++++++---- 3 files changed, 21 insertions(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp index 8841429fa..9dcd43208 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp @@ -492,13 +492,13 @@ QVariant UAVObjectField::getValue(quint32 index) return QVariant(); } -void UAVObjectField::setValue(const QVariant& value, quint32 index) +bool UAVObjectField::setValue(const QVariant& value, quint32 index) { QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds if ( index >= numElements ) { - return; + return false; } // Get metadata UAVObject::Metadata mdata = obj->getMetadata(); @@ -552,8 +552,11 @@ void UAVObjectField::setValue(const QVariant& value, quint32 index) case ENUM: { qint8 tmpenum = options.indexOf( value.toString() ); - Q_ASSERT(tmpenum >= 0); // To catch any programming errors where we set invalid values - memcpy(&data[offset + numBytesPerElement*index], &tmpenum, numBytesPerElement); +// Q_ASSERT(tmpenum >= 0); // To catch any programming errors where we set invalid values + if(tmpenum < 0) + return false; + else + memcpy(&data[offset + numBytesPerElement*index], &tmpenum, numBytesPerElement); break; } case STRING: @@ -570,6 +573,7 @@ void UAVObjectField::setValue(const QVariant& value, quint32 index) } } } + return true; } double UAVObjectField::getDouble(quint32 index) diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h index 9ae9d0d72..93c86c6fe 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h @@ -56,7 +56,7 @@ public: qint32 pack(quint8* dataOut); qint32 unpack(const quint8* dataIn); QVariant getValue(quint32 index = 0); - void setValue(const QVariant& data, quint32 index = 0); + bool setValue(const QVariant& data, quint32 index = 0); double getDouble(quint32 index = 0); void setDouble(double value, quint32 index = 0); quint32 getDataOffset(); diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp index 285bc7cbf..3733864c2 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp @@ -153,6 +153,7 @@ void UAVSettingsImportExportFactory::importUAVSettings() // - Update each field // - Issue and "updated" command bool error=false; + bool setError=false; QDomNode field = node.firstChild(); while(!field.isNull()) { QDomElement f = field.toElement(); @@ -161,16 +162,21 @@ void UAVSettingsImportExportFactory::importUAVSettings() if (uavfield) { QStringList list = f.attribute("values").split(","); if (list.length() == 1) { - uavfield->setValue(f.attribute("values")); + if (false == uavfield->setValue(f.attribute("values"))) { + qDebug() << "setValue returned false on: " << uavObjectName << f.attribute("values"); + setError = true; + } } else { // This is an enum: int i=0; QStringList list = f.attribute("values").split(","); foreach (QString element, list) { - uavfield->setValue(element,i++); + if (false == uavfield->setValue(element,i++)) { + qDebug() << "setValue returned false on: " << uavObjectName << list; + setError = true; + } } } - error = false; } else { error = true; } @@ -183,7 +189,9 @@ void UAVSettingsImportExportFactory::importUAVSettings() } else if (uavObjectID != obj->getObjID()) { qDebug() << "Mismatch for Object " << uavObjectName << uavObjectID << " - " << obj->getObjID(); swui.addLine(uavObjectName, "Warning (ObjectID mismatch)", true); - } else + } else if (setError) { + swui.addLine(uavObjectName, "Warning (Objects field value(s) invalid)", false); + } else swui.addLine(uavObjectName, "OK", true); } } From 1f60f80053db5ac998cd26763812a58bc1cddd67 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sat, 26 Nov 2011 22:57:33 +0200 Subject: [PATCH 05/24] Bring back the ERASE_FLASH option support for SettingsEraseFirmware --- flight/CopterControl/System/coptercontrol.c | 16 +++++++++++----- flight/CopterControl/System/pios_board.c | 2 ++ 2 files changed, 13 insertions(+), 5 deletions(-) diff --git a/flight/CopterControl/System/coptercontrol.c b/flight/CopterControl/System/coptercontrol.c index 7d4ca0627..a7cd909d9 100644 --- a/flight/CopterControl/System/coptercontrol.c +++ b/flight/CopterControl/System/coptercontrol.c @@ -70,6 +70,12 @@ int main() * */ PIOS_Board_Init(); +#ifdef ERASE_FLASH + PIOS_Flash_W25X_EraseChip(); + PIOS_LED_Off(LED1); + while (1) ; +#endif + /* Initialize modules */ MODULE_INITIALISE_ALL @@ -82,11 +88,11 @@ int main() /* If all is well we will never reach here as the scheduler will now be running. */ /* Do some indication to user that something bad just happened */ - PIOS_LED_Off(LED1); \ - for(;;) { \ - PIOS_LED_Toggle(LED1); \ - PIOS_DELAY_WaitmS(100); \ - }; + PIOS_LED_Off(LED1); + while (1) { + PIOS_LED_Toggle(LED1); + PIOS_DELAY_WaitmS(100); + } return 0; } diff --git a/flight/CopterControl/System/pios_board.c b/flight/CopterControl/System/pios_board.c index f895d8e2b..e80d4e51a 100644 --- a/flight/CopterControl/System/pios_board.c +++ b/flight/CopterControl/System/pios_board.c @@ -1430,7 +1430,9 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_USB_HID */ PIOS_IAP_Init(); +#ifndef ERASE_FLASH PIOS_WDG_Init(); +#endif } /** From dfd18d43b5328827b215277b4592b20d10f32756 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 26 Nov 2011 22:06:21 +0100 Subject: [PATCH 06/24] GCS/Scope: CSV export exports non-interpolated data --- ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp index 2270178cd..fe322f06b 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp @@ -710,7 +710,7 @@ int ScopeGadgetWidget::csvLoggingInsertData() } else { - ss << QString().sprintf("%3.6g",plotData2->yData->last()/pow(10,plotData2->scalePower)); + ss << QString().sprintf("%3.6g",plotData2->yDataHistory->last()/pow(10,plotData2->scalePower)); m_csvLoggingDataValid=1; } } From 5af9a2558c8f61a87d9d3db506ccc6a5eb5b61ce Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 26 Nov 2011 22:06:46 +0100 Subject: [PATCH 07/24] GCS/Scope: Make smooth interpolation (and internal sum) be long term correct despite limited floating point accuracy, but keep constant overhead --- .../src/plugins/scope/plotdata.cpp | 31 ++++++++++++++++--- .../openpilotgcs/src/plugins/scope/plotdata.h | 2 ++ .../plugins/scope/scopegadgetoptionspage.ui | 4 +-- 3 files changed, 31 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/scope/plotdata.cpp b/ground/openpilotgcs/src/plugins/scope/plotdata.cpp index fdcb75a83..e05bf7a1b 100644 --- a/ground/openpilotgcs/src/plugins/scope/plotdata.cpp +++ b/ground/openpilotgcs/src/plugins/scope/plotdata.cpp @@ -55,6 +55,8 @@ PlotData::PlotData(QString p_uavObject, QString p_uavField) scalePower = 0; interpolationSamples = 1; interpolationSum = 0.0f; + correctionSum = 0.0f; + correctionCount = 0; yMinimum = 0; yMaximum = 0; @@ -95,12 +97,23 @@ bool SequencialPlotData::append(UAVObject* obj) if (field) { //Shift data forward and put the new value at the front - yDataHistory->append( valueAsDouble(obj, field) * pow(10, scalePower)); - interpolationSum += valueAsDouble(obj, field) * pow(10, scalePower); + + // calculate interpolated (smoothed) value + double currentValue = valueAsDouble(obj, field) * pow(10, scalePower); + yDataHistory->append( currentValue ); + interpolationSum += currentValue; if(yDataHistory->size() > interpolationSamples) { interpolationSum -= yDataHistory->first(); yDataHistory->pop_front(); } + // make sure to correct the sum every interpolationSamples steps to prevent it + // from running away due to flouting point rounding errors + correctionSum += currentValue; + if (++correctionCount >= interpolationSamples) { + interpolationSum = correctionSum; + correctionSum = 0.0f; + correctionCount = 0; + } yData->append(interpolationSum/yDataHistory->size()); if (yData->size() > m_xWindowSize) { yData->pop_front(); @@ -127,12 +140,22 @@ bool ChronoPlotData::append(UAVObject* obj) //Put the new value at the front QDateTime NOW = QDateTime::currentDateTime(); - yDataHistory->append( valueAsDouble(obj, field) * pow(10, scalePower)); - interpolationSum += valueAsDouble(obj, field) * pow(10, scalePower); + // calculate interpolated (smoothed) value + double currentValue = valueAsDouble(obj, field) * pow(10, scalePower); + yDataHistory->append( currentValue ); + interpolationSum += currentValue; if(yDataHistory->size() > interpolationSamples) { interpolationSum -= yDataHistory->first(); yDataHistory->pop_front(); } + // make sure to correct the sum every interpolationSamples steps to prevent it + // from running away due to flouting point rounding errors + correctionSum += currentValue; + if (++correctionCount >= interpolationSamples) { + interpolationSum = correctionSum; + correctionSum = 0.0f; + correctionCount = 0; + } double valueX = NOW.toTime_t() + NOW.time().msec() / 1000.0; double valueY = interpolationSum/yDataHistory->size(); diff --git a/ground/openpilotgcs/src/plugins/scope/plotdata.h b/ground/openpilotgcs/src/plugins/scope/plotdata.h index 0b87c9937..a547f2b91 100644 --- a/ground/openpilotgcs/src/plugins/scope/plotdata.h +++ b/ground/openpilotgcs/src/plugins/scope/plotdata.h @@ -74,6 +74,8 @@ public: int scalePower; //This is the power to which each value must be raised int interpolationSamples; double interpolationSum; + double correctionSum; + int correctionCount; double yMinimum; double yMaximum; double m_xWindowSize; diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui index 147f972f1..b3d22faa0 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui @@ -162,7 +162,7 @@ - Smooth Interpolation: + Display smoothed interpolation: @@ -294,7 +294,7 @@ Update - Log data to csv file + Log data to csv file (not interpolated) From 15c1ca4af117e29326ef85196e0fa83b029c53df Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 26 Nov 2011 22:51:20 +0100 Subject: [PATCH 08/24] GVS/Scope: Bugfix: Export all known data points into CSV not just one per screen redraw --- .../src/plugins/scope/scopegadgetwidget.cpp | 78 +++++++++++-------- .../src/plugins/scope/scopegadgetwidget.h | 2 + 2 files changed, 47 insertions(+), 33 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp index fe322f06b..12f6974b8 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp @@ -447,6 +447,7 @@ void ScopeGadgetWidget::uavObjectReceived(UAVObject* obj) foreach(PlotData* plotData, m_curvesData.values()) { if (plotData->append(obj)) m_csvLoggingDataUpdated=1; } + csvLoggingAddData(); } void ScopeGadgetWidget::replotNewData() @@ -610,6 +611,7 @@ int ScopeGadgetWidget::csvLoggingStart() m_csvLoggingStartTime = NOW; m_csvLoggingHeaderSaved=0; m_csvLoggingDataSaved=0; + m_csvLoggingBuffer.clear(); QDir PathCheck(m_csvLoggingPath); if (!PathCheck.exists()) { @@ -677,13 +679,50 @@ int ScopeGadgetWidget::csvLoggingInsertHeader() return 0; } +int ScopeGadgetWidget::csvLoggingAddData() +{ + if (!m_csvLoggingStarted) return -1; + m_csvLoggingDataValid=0; + QDateTime NOW = QDateTime::currentDateTime(); + QString tempString; + + QTextStream ss( &tempString ); + ss << NOW.toString("yyyy-MM-dd") << ", " << NOW.toString("hh:mm:ss.z") << ", " ; + +#if QT_VERSION >= 0x040700 + ss <<(NOW.toMSecsSinceEpoch() - m_csvLoggingStartTime.toMSecsSinceEpoch())/1000.00; +#else + ss <<(NOW.toTime_t() - m_csvLoggingStartTime.toTime_t()); +#endif + ss << ", " << m_csvLoggingConnected << ", " << m_csvLoggingDataUpdated; + m_csvLoggingDataUpdated=0; + + foreach(PlotData* plotData2, m_curvesData.values()) + { + ss << ", "; + if (plotData2->xData->isEmpty ()) + { + } + else + { + ss << QString().sprintf("%3.6g",plotData2->yDataHistory->last()/pow(10,plotData2->scalePower)); + m_csvLoggingDataValid=1; + } + } + ss << endl; + if (m_csvLoggingDataValid) + { + QTextStream ts( &m_csvLoggingBuffer ); + ts << tempString; + } + + return 0; +} + int ScopeGadgetWidget::csvLoggingInsertData() { if (!m_csvLoggingStarted) return -1; m_csvLoggingDataSaved=1; - m_csvLoggingDataValid=0; - QDateTime NOW = QDateTime::currentDateTime(); - QString tempString; if(m_csvLoggingFile.open(QIODevice::WriteOnly | QIODevice::Append)== FALSE) { @@ -691,38 +730,11 @@ int ScopeGadgetWidget::csvLoggingInsertData() } else { - QTextStream ss( &tempString ); - ss << NOW.toString("yyyy-MM-dd") << ", " << NOW.toString("hh:mm:ss.z") << ", " ; - -#if QT_VERSION >= 0x040700 - ss <<(NOW.toMSecsSinceEpoch() - m_csvLoggingStartTime.toMSecsSinceEpoch())/1000.00; -#else - ss <<(NOW.toTime_t() - m_csvLoggingStartTime.toTime_t()); -#endif - ss << ", " << m_csvLoggingConnected << ", " << m_csvLoggingDataUpdated; - m_csvLoggingDataUpdated=0; - - foreach(PlotData* plotData2, m_curvesData.values()) - { - ss << ", "; - if (plotData2->xData->isEmpty ()) - { - } - else - { - ss << QString().sprintf("%3.6g",plotData2->yDataHistory->last()/pow(10,plotData2->scalePower)); - m_csvLoggingDataValid=1; - } - } - ss << endl; - if (m_csvLoggingDataValid) - { - QTextStream ts( &m_csvLoggingFile ); - ts << tempString; - } + QTextStream ts( &m_csvLoggingFile ); + ts << m_csvLoggingBuffer; m_csvLoggingFile.close(); } - + m_csvLoggingBuffer.clear(); return 0; } diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h index 09e79d6b0..98da3beb6 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.h @@ -166,11 +166,13 @@ private: QString m_csvLoggingName; QString m_csvLoggingPath; + QString m_csvLoggingBuffer; QFile m_csvLoggingFile; QMutex mutex; int csvLoggingInsertHeader(); + int csvLoggingAddData(); int csvLoggingInsertData(); void deleteLegend(); From 5bc1a107744366018def24b6b84ea17f36b54209 Mon Sep 17 00:00:00 2001 From: zedamota Date: Mon, 28 Nov 2011 12:12:26 +0000 Subject: [PATCH 09/24] Fixes the "halt" and "rescue" problems --- .../src/plugins/rawhid/rawhid.pro | 6 ++- .../src/plugins/rawhid/rawhidplugin.h | 2 +- .../src/plugins/rawhid/usbmonitor.h | 1 - .../src/plugins/rawhid/usbmonitor_win.cpp | 40 ++++++++++++++--- .../src/plugins/rawhid/usbsignalfilter.cpp | 22 ++++++++++ .../src/plugins/rawhid/usbsignalfilter.h | 21 +++++++++ .../src/plugins/uploader/op_dfu.cpp | 43 ++++++++++++------- .../src/plugins/uploader/op_dfu.h | 1 + 8 files changed, 111 insertions(+), 25 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/rawhid/usbsignalfilter.cpp create mode 100644 ground/openpilotgcs/src/plugins/rawhid/usbsignalfilter.h diff --git a/ground/openpilotgcs/src/plugins/rawhid/rawhid.pro b/ground/openpilotgcs/src/plugins/rawhid/rawhid.pro index 4a3557982..f857ef72a 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/rawhid.pro +++ b/ground/openpilotgcs/src/plugins/rawhid/rawhid.pro @@ -7,9 +7,11 @@ HEADERS += rawhid_global.h \ rawhid.h \ pjrc_rawhid.h \ rawhid_const.h \ - usbmonitor.h + usbmonitor.h \ + usbsignalfilter.h SOURCES += rawhidplugin.cpp \ - rawhid.cpp + rawhid.cpp \ + usbsignalfilter.cpp FORMS += RESOURCES += DEFINES += RAWHID_LIBRARY diff --git a/ground/openpilotgcs/src/plugins/rawhid/rawhidplugin.h b/ground/openpilotgcs/src/plugins/rawhid/rawhidplugin.h index 0bbeac524..ee9aa49aa 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/rawhidplugin.h +++ b/ground/openpilotgcs/src/plugins/rawhid/rawhidplugin.h @@ -31,7 +31,7 @@ #include "rawhid_global.h" #include "rawhid.h" #include "usbmonitor.h" - +#include "usbsignalfilter.h" #include "coreplugin/iconnection.h" #include diff --git a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor.h b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor.h index 1d8eea087..fd114042f 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor.h +++ b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor.h @@ -202,5 +202,4 @@ private: #endif }; - #endif // USBMONITOR_H diff --git a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_win.cpp b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_win.cpp index c2ab1fa9c..aa653179a 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_win.cpp +++ b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_win.cpp @@ -78,6 +78,15 @@ USBMonitor::~USBMonitor() QList USBMonitor::availableDevices(int vid, int pid, int bcdDeviceMSB, int bcdDeviceLSB) { QList allPorts = availableDevices(); + qDebug()<<"USBMonitor::availableDevices list off all ports:"; + qDebug()<<"USBMonitor::availableDevices total ports:"< thePortsWeWant; qDebug()<<"USBMonitor::availableDevices bcdLSB="< USBMonitor::availableDevices(int vid, int pid, int bcdDeviceM ( (port.bcdDevice&0x00ff) ==bcdDeviceLSB || bcdDeviceLSB==-1)) thePortsWeWant.append(port); } + qDebug()<<"USBMonitor::availableDevices list off matching ports vid pid bcdMSD bcdLSD:"< +void USBSignalFilter::m_deviceDiscovered(USBPortInfo port) +{ + if((port.vendorID==m_vid || m_vid==-1) && (port.productID==m_pid || m_pid==-1) && ((port.bcdDevice>>8)==m_boardModel || m_boardModel==-1) && + ( (port.bcdDevice&0x00ff) ==m_runState || m_runState==-1)) + { + qDebug()<<"USBSignalFilter emit device discovered"; + emit deviceDiscovered(); + } +} + +USBSignalFilter::USBSignalFilter(int vid, int pid, int boardModel, int runState): + m_vid(vid), + m_pid(pid), + m_boardModel(boardModel), + m_runState(runState) +{ + connect(USBMonitor::instance(),SIGNAL(deviceDiscovered(USBPortInfo)),this,SLOT(m_deviceDiscovered(USBPortInfo))); +} + + diff --git a/ground/openpilotgcs/src/plugins/rawhid/usbsignalfilter.h b/ground/openpilotgcs/src/plugins/rawhid/usbsignalfilter.h new file mode 100644 index 000000000..6a9310d46 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/rawhid/usbsignalfilter.h @@ -0,0 +1,21 @@ +#ifndef USBSIGNALFILTER_H +#define USBSIGNALFILTER_H +#include +#include "usbmonitor.h" + +class RAWHID_EXPORT USBSignalFilter : public QObject +{ + Q_OBJECT +private: + int m_vid; + int m_pid; + int m_boardModel; + int m_runState; +signals: + void deviceDiscovered(); +private slots: + void m_deviceDiscovered(USBPortInfo port); +public: + USBSignalFilter(int vid, int pid, int boardModel, int runState); +}; +#endif // USBSIGNALFILTER_H diff --git a/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp b/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp index 549201989..961103d22 100644 --- a/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp @@ -80,30 +80,41 @@ DFUObject::DFUObject(bool _debug,bool _use_serial,QString portname): } else { + mready = false; QEventLoop m_eventloop; QTimer::singleShot(200,&m_eventloop, SLOT(quit())); m_eventloop.exec(); QList devices; devices = USBMonitor::instance()->availableDevices(0x20a0,-1,-1,USBMonitor::Bootloader); - if (devices.length()==1) { - hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0); + if (devices.length()==1 && hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0)==1) { qDebug()<<"OP_DFU detected first time"; + mready=true; } else { // Wait for the board to appear on the USB bus: - connect(USBMonitor::instance(), SIGNAL(deviceDiscovered(USBPortInfo)),&m_eventloop, SLOT(quit())); - QTimer::singleShot(15000,&m_eventloop, SLOT(quit())); - m_eventloop.exec(); - disconnect(USBMonitor::instance(), SIGNAL(deviceDiscovered(USBPortInfo)),&m_eventloop, SLOT(quit())); - devices = USBMonitor::instance()->availableDevices(0x20a0,-1,-1,USBMonitor::Bootloader); - if (devices.length()==1) { - QTimer::singleShot(1000,&m_eventloop, SLOT(quit())); - m_eventloop.exec(); - hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0); - qDebug()<<"OP_DFU detected after delay"; - } - else { - qDebug() << devices.length() << " device(s) detected, don't know what to do!"; - mready = false; + USBSignalFilter filter(0x20a0,-1,-1,USBMonitor::Bootloader); + connect(&filter, SIGNAL(deviceDiscovered()),&m_eventloop, SLOT(quit())); + for(int x=0;x<4;++x) + { + qDebug()<<"OP_DFU trying to detect bootloader:"<availableDevices(0x20a0,-1,-1,USBMonitor::Bootloader); + if (devices.length()==1) { + if(hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0)==1) + { + qDebug()<<"OP_DFU detected after delay"; + mready=true; + break; + } + } + 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 233e8274f..79624b546 100644 --- a/ground/openpilotgcs/src/plugins/uploader/op_dfu.h +++ b/ground/openpilotgcs/src/plugins/uploader/op_dfu.h @@ -4,6 +4,7 @@ #include #include #include +#include #include #include #include From fcbb00f757d6cb250a965a250f766952a1515d2a Mon Sep 17 00:00:00 2001 From: zedamota Date: Tue, 29 Nov 2011 17:01:02 +0000 Subject: [PATCH 10/24] config outputs now uses dropdown boxes for the update freq. --- .../src/plugins/config/configoutputwidget.cpp | 64 ++-- .../openpilotgcs/src/plugins/config/output.ui | 324 ++++++++++++------ 2 files changed, 265 insertions(+), 123 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index 53553ac2e..0aa4ee809 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -81,10 +81,10 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren // Connect the help button connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - addWidget(m_config->outputRate3); - addWidget(m_config->outputRate2); - addWidget(m_config->outputRate1); - + addWidget(m_config->cb_outputRate4); + addWidget(m_config->cb_outputRate3); + addWidget(m_config->cb_outputRate2); + addWidget(m_config->cb_outputRate1); addWidget(m_config->spinningArmed); UAVObjectManager *objManager = pm->getObject(); @@ -277,8 +277,17 @@ void ConfigOutputWidget::refreshWidgetsValues() m_config->spinningArmed->setChecked(actuatorSettingsData.MotorsSpinWhileArmed == ActuatorSettings::MOTORSSPINWHILEARMED_TRUE); // Get Output rates for both banks - m_config->outputRate1->setValue(actuatorSettingsData.ChannelUpdateFreq[0]); - m_config->outputRate2->setValue(actuatorSettingsData.ChannelUpdateFreq[1]); + if(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]))==-1) + { + m_config->cb_outputRate1->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])); + } + if(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]))==-1) + { + m_config->cb_outputRate2->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])); + } + m_config->cb_outputRate1->setCurrentIndex(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]))); + m_config->cb_outputRate2->setCurrentIndex(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]))); + UAVObjectUtilManager* utilMngr = pm->getObject(); if (utilMngr) { int board = utilMngr->getBoardModel(); @@ -288,24 +297,34 @@ void ConfigOutputWidget::refreshWidgetsValues() m_config->chBank2->setText("4"); m_config->chBank3->setText("5,7-8"); m_config->chBank4->setText("6,9-10"); - m_config->outputRate1->setEnabled(true); - m_config->outputRate2->setEnabled(true); - m_config->outputRate3->setEnabled(true); - m_config->outputRate4->setEnabled(true); - m_config->outputRate3->setValue(actuatorSettingsData.ChannelUpdateFreq[2]); - m_config->outputRate4->setValue(actuatorSettingsData.ChannelUpdateFreq[3]); + m_config->cb_outputRate1->setEnabled(true); + m_config->cb_outputRate2->setEnabled(true); + m_config->cb_outputRate3->setEnabled(true); + m_config->cb_outputRate4->setEnabled(true); + if(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]))==-1) + { + m_config->cb_outputRate3->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[2])); + } + if(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]))==-1) + { + m_config->cb_outputRate4->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])); + } + m_config->cb_outputRate3->setCurrentIndex(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]))); + m_config->cb_outputRate4->setCurrentIndex(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]))); } else if ((board & 0xff00) == 256 ) { // Mainboard family - m_config->outputRate1->setEnabled(true); - m_config->outputRate2->setEnabled(true); - m_config->outputRate3->setEnabled(false); - m_config->outputRate4->setEnabled(false); + m_config->cb_outputRate1->setEnabled(true); + m_config->cb_outputRate2->setEnabled(true); + m_config->cb_outputRate3->setEnabled(false); + m_config->cb_outputRate4->setEnabled(false); m_config->chBank1->setText("1-4"); m_config->chBank2->setText("5-8"); m_config->chBank3->setText("-"); m_config->chBank4->setText("-"); - m_config->outputRate3->setValue(0); - m_config->outputRate4->setValue(0); + m_config->cb_outputRate3->addItem("0"); + m_config->cb_outputRate3->setCurrentIndex(m_config->cb_outputRate3->findText("0")); + m_config->cb_outputRate4->addItem("0"); + m_config->cb_outputRate4->setCurrentIndex(m_config->cb_outputRate4->findText("0")); } } @@ -342,11 +361,10 @@ void ConfigOutputWidget::updateObjectsFromWidgets() } // Set update rates - actuatorSettingsData.ChannelUpdateFreq[0] = m_config->outputRate1->value(); - actuatorSettingsData.ChannelUpdateFreq[1] = m_config->outputRate2->value(); - actuatorSettingsData.ChannelUpdateFreq[2] = m_config->outputRate3->value(); - actuatorSettingsData.ChannelUpdateFreq[3] = m_config->outputRate4->value(); - + actuatorSettingsData.ChannelUpdateFreq[0] = m_config->cb_outputRate1->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt(); // Apply settings actuatorSettings->setData(actuatorSettingsData); } diff --git a/ground/openpilotgcs/src/plugins/config/output.ui b/ground/openpilotgcs/src/plugins/config/output.ui index 47940e1ae..de87ef7eb 100644 --- a/ground/openpilotgcs/src/plugins/config/output.ui +++ b/ground/openpilotgcs/src/plugins/config/output.ui @@ -38,102 +38,6 @@ 2 - - - - false - - - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. - - - 400 - - - - - - - - - - - Qt::AlignCenter - - - - - - - - - - - Qt::AlignCenter - - - - - - - - - - - Qt::AlignCenter - - - - - - - false - - - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. - - - 400 - - - - - - - false - - - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. - - - 400 - - - - - - - false - - - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. - - - 400 - - - - - - - - - - - Qt::AlignCenter - - - @@ -206,6 +110,230 @@ Leave at 50Hz for fixed wing. + + + + false + + + Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. +Leave at 50Hz for fixed wing. + + + + 50 + + + + + 60 + + + + + 125 + + + + + 165 + + + + + 270 + + + + + 330 + + + + + 400 + + + + + + + + false + + + Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. +Leave at 50Hz for fixed wing. + + + + 50 + + + + + 60 + + + + + 125 + + + + + 165 + + + + + 270 + + + + + 330 + + + + + 400 + + + + + + + + false + + + Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. +Leave at 50Hz for fixed wing. + + + + 50 + + + + + 60 + + + + + 125 + + + + + 165 + + + + + 270 + + + + + 330 + + + + + 400 + + + + + + + + false + + + Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. +Leave at 50Hz for fixed wing. + + + + 50 + + + + + 60 + + + + + 125 + + + + + 165 + + + + + 270 + + + + + 330 + + + + + 400 + + + + + + + + - + + + Qt::AlignCenter + + + + + + + - + + + Qt::AlignCenter + + + + + + + - + + + Qt::AlignCenter + + + + + + + - + + + Qt::AlignCenter + + + @@ -351,10 +479,6 @@ Applies and Saves all settings to SD - outputRate1 - outputRate2 - outputRate3 - outputRate4 channelOutTest saveRCOutputToRAM saveRCOutputToSD From a0cd71abe671eddda309cb76f610cbaf7da4deeb Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Wed, 30 Nov 2011 08:18:23 +0100 Subject: [PATCH 11/24] UAVObjects ; Modules/ManualControl: Fixed metadata interface and segfault when retrieving it --- flight/Modules/Actuator/actuator.c | 2 +- flight/Modules/ManualControl/manualcontrol.c | 8 ++++---- flight/UAVObjects/inc/uavobjecttemplate.h | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/flight/Modules/Actuator/actuator.c b/flight/Modules/Actuator/actuator.c index f50848ddc..9cc856487 100644 --- a/flight/Modules/Actuator/actuator.c +++ b/flight/Modules/Actuator/actuator.c @@ -207,7 +207,7 @@ static void actuatorTask(void* parameters) nMixers ++; } } - if((nMixers < 2) && !ActuatorCommandReadOnly(dummy)) //Nothing can fly with less than two mixers. + if((nMixers < 2) && !ActuatorCommandReadOnly()) //Nothing can fly with less than two mixers. { setFailsafe(); // So that channels like PWM buzzer keep working continue; diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index db98283df..19b99148c 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -189,19 +189,19 @@ static void manualControlTask(void *parameters) lastActivityTime = lastSysTime; } - if (ManualControlCommandReadOnly(&cmd)) { + if (ManualControlCommandReadOnly()) { FlightTelemetryStatsData flightTelemStats; FlightTelemetryStatsGet(&flightTelemStats); if(flightTelemStats.Status != FLIGHTTELEMETRYSTATS_STATUS_CONNECTED) { /* trying to fly via GCS and lost connection. fall back to transmitter */ UAVObjMetadata metadata; - UAVObjGetMetadata(&cmd, &metadata); + ManualControlCommandGetMetadata(&metadata); metadata.access = ACCESS_READWRITE; - UAVObjSetMetadata(&cmd, &metadata); + ManualControlCommandSetMetadata(&metadata); } } - if (!ManualControlCommandReadOnly(&cmd)) { + if (!ManualControlCommandReadOnly()) { bool valid_input_detected = true; diff --git a/flight/UAVObjects/inc/uavobjecttemplate.h b/flight/UAVObjects/inc/uavobjecttemplate.h index 9564d05d2..f106dd8ba 100644 --- a/flight/UAVObjects/inc/uavobjecttemplate.h +++ b/flight/UAVObjects/inc/uavobjecttemplate.h @@ -67,7 +67,7 @@ #define $(NAME)InstUpdated(instId) UAVObjUpdated($(NAME)Handle(), instId) #define $(NAME)GetMetadata(dataOut) UAVObjGetMetadata($(NAME)Handle(), dataOut) #define $(NAME)SetMetadata(dataIn) UAVObjSetMetadata($(NAME)Handle(), dataIn) -#define $(NAME)ReadOnly(dataIn) UAVObjReadOnly($(NAME)Handle()) +#define $(NAME)ReadOnly() UAVObjReadOnly($(NAME)Handle()) // Object data typedef struct { From 783510de57952286945a14c6926f363cb66b91ed Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 4 Dec 2011 22:31:07 -0600 Subject: [PATCH 12/24] Add break that Brian caught --- ground/openpilotgcs/src/plugins/config/inputchannelform.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp index 1eca667a8..9bb441790 100644 --- a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp @@ -94,6 +94,7 @@ void inputChannelForm::groupUpdated() break; case ManualControlSettings::CHANNELGROUPS_GCS: count = 5; + break; case ManualControlSettings::CHANNELGROUPS_NONE: count = 0; break; From 354867bdb1a78082510decb9435230afc0a93edf Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 4 Dec 2011 22:33:27 -0600 Subject: [PATCH 13/24] Keep indenting using spaces. --- ground/openpilotgcs/src/plugins/config/inputchannelform.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp index 9bb441790..98f71ea31 100644 --- a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp @@ -94,7 +94,7 @@ void inputChannelForm::groupUpdated() break; case ManualControlSettings::CHANNELGROUPS_GCS: count = 5; - break; + break; case ManualControlSettings::CHANNELGROUPS_NONE: count = 0; break; From 8a9b5083927938079b39bcc459696eeeb56cd784 Mon Sep 17 00:00:00 2001 From: Michael Schulz Date: Mon, 5 Dec 2011 21:14:52 +0100 Subject: [PATCH 14/24] layout fix for last 2 columns of outputchannelform --- .../src/plugins/config/outputchannelform.ui | 40 ++++++++++++++++++- 1 file changed, 38 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.ui b/ground/openpilotgcs/src/plugins/config/outputchannelform.ui index 49924e06e..4988b5e7d 100644 --- a/ground/openpilotgcs/src/plugins/config/outputchannelform.ui +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.ui @@ -136,6 +136,18 @@ + + + 0 + 0 + + + + + 25 + 0 + + Check to invert the channel. @@ -143,6 +155,18 @@ + + + 0 + 0 + + + + + 25 + 0 + + Output mode @@ -213,11 +237,17 @@ - + 0 0 + + + 25 + 0 + + Rev. @@ -226,11 +256,17 @@ - + 0 0 + + + 25 + 0 + + Link From 612b0301c18a67d1824614ffef3dbdc246975bcb Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Tue, 6 Dec 2011 17:56:33 +0200 Subject: [PATCH 15/24] Dummy commit to check forum RSS import --- MILESTONES.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/MILESTONES.txt b/MILESTONES.txt index b146d09b7..c71eff40f 100644 --- a/MILESTONES.txt +++ b/MILESTONES.txt @@ -188,4 +188,3 @@ An incomplete list of some future Milestones is below: * First over 5km navigation flight * First "Follow Me" navigation flight * First Channel Crossing with OpenPilot - From 09d2cda0c014b3d56df546844a22a8210737e655 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Tue, 6 Dec 2011 19:40:28 +0200 Subject: [PATCH 16/24] Dummy commit to check forum RSS import --- MILESTONES.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/MILESTONES.txt b/MILESTONES.txt index c71eff40f..b146d09b7 100644 --- a/MILESTONES.txt +++ b/MILESTONES.txt @@ -188,3 +188,4 @@ An incomplete list of some future Milestones is below: * First over 5km navigation flight * First "Follow Me" navigation flight * First Channel Crossing with OpenPilot + From e82f7b06f537194f1495e138e08df262b42834b3 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Tue, 6 Dec 2011 19:50:15 +0200 Subject: [PATCH 17/24] Dummy commit to check forum RSS import Sorry guys, but this RSS import must be finally fixed. --- MILESTONES.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/MILESTONES.txt b/MILESTONES.txt index b146d09b7..c71eff40f 100644 --- a/MILESTONES.txt +++ b/MILESTONES.txt @@ -188,4 +188,3 @@ An incomplete list of some future Milestones is below: * First over 5km navigation flight * First "Follow Me" navigation flight * First Channel Crossing with OpenPilot - From 5833d500571563551156f8045c4b9dac291c6401 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Tue, 6 Dec 2011 19:57:28 +0200 Subject: [PATCH 18/24] Dummy commit to check forum RSS import (disable HTML during import) --- MILESTONES.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/MILESTONES.txt b/MILESTONES.txt index c71eff40f..b146d09b7 100644 --- a/MILESTONES.txt +++ b/MILESTONES.txt @@ -188,3 +188,4 @@ An incomplete list of some future Milestones is below: * First over 5km navigation flight * First "Follow Me" navigation flight * First Channel Crossing with OpenPilot + From da819809c897a426e02e9fbc75dcfb0f467e2a52 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Tue, 6 Dec 2011 20:09:16 +0200 Subject: [PATCH 19/24] MILESTONES: First OpenPilot over 1km FixedWing navigation flight --- MILESTONES.txt | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/MILESTONES.txt b/MILESTONES.txt index b146d09b7..14242d2f2 100644 --- a/MILESTONES.txt +++ b/MILESTONES.txt @@ -157,6 +157,11 @@ C: Anders Johansson (dezent) D: November 2011 V: http://www.youtube.com/watch?v=Xfas2TUhOPw +M: First OpenPilot over 1km FixedWing navigation flight +C: Eric Price (Corvus Corax) +D: December 2011 +V: http://www.youtube.com/watch?v=nWNWuUiUTNg + M: First Altitude Hold using Sonar C: @@ -184,8 +189,6 @@ An incomplete list of some future Milestones is below: * First fixed wing navigation flight * First Multirotor navigation flight * First Helicopter navigation flight -* First over 1km navigation flight * First over 5km navigation flight * First "Follow Me" navigation flight * First Channel Crossing with OpenPilot - From 6dc121fda6e1065ba1e4f5eb61262ba313ca8c91 Mon Sep 17 00:00:00 2001 From: naiiawah Date: Tue, 6 Dec 2011 22:20:46 -0700 Subject: [PATCH 20/24] Updated fix to preserve assert behavior by adding a check routine that is called before trying to add an item. --- .../src/plugins/uavobjects/uavobjectfield.cpp | 49 ++++++++++++++++--- .../src/plugins/uavobjects/uavobjectfield.h | 3 +- .../uavsettingsimportexportfactory.cpp | 15 +++--- 3 files changed, 53 insertions(+), 14 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp index 9dcd43208..da71fd943 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp @@ -492,7 +492,7 @@ QVariant UAVObjectField::getValue(quint32 index) return QVariant(); } -bool UAVObjectField::setValue(const QVariant& value, quint32 index) +bool UAVObjectField::checkValue(const QVariant& value, quint32 index) { QMutexLocker locker(obj->getMutex()); // Check that index is not out of bounds @@ -504,6 +504,45 @@ bool UAVObjectField::setValue(const QVariant& value, quint32 index) UAVObject::Metadata mdata = obj->getMetadata(); // Update value if the access mode permits if ( mdata.gcsAccess == UAVObject::ACCESS_READWRITE ) + { + switch (type) + { + case INT8: + case INT16: + case INT32: + case UINT8: + case UINT16: + case UINT32: + case FLOAT32: + case STRING: + return true; + break; + case ENUM: + { + qint8 tmpenum = options.indexOf( value.toString() ); + return ((tmpenum < 0) ? false : true); + break; + } + default: + qDebug() << "checkValue: other types" << type; + Q_ASSERT(0); // To catch any programming errors where we tried to test invalid values + break; + } + } +} + +void UAVObjectField::setValue(const QVariant& value, quint32 index) +{ + QMutexLocker locker(obj->getMutex()); + // Check that index is not out of bounds + if ( index >= numElements ) + { + return; + } + // Get metadata + UAVObject::Metadata mdata = obj->getMetadata(); + // Update value if the access mode permits + if ( mdata.gcsAccess == UAVObject::ACCESS_READWRITE ) { switch (type) { @@ -552,11 +591,8 @@ bool UAVObjectField::setValue(const QVariant& value, quint32 index) case ENUM: { qint8 tmpenum = options.indexOf( value.toString() ); -// Q_ASSERT(tmpenum >= 0); // To catch any programming errors where we set invalid values - if(tmpenum < 0) - return false; - else - memcpy(&data[offset + numBytesPerElement*index], &tmpenum, numBytesPerElement); + Q_ASSERT(tmpenum >= 0); // To catch any programming errors where we set invalid values + memcpy(&data[offset + numBytesPerElement*index], &tmpenum, numBytesPerElement); break; } case STRING: @@ -573,7 +609,6 @@ bool UAVObjectField::setValue(const QVariant& value, quint32 index) } } } - return true; } double UAVObjectField::getDouble(quint32 index) diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h index 93c86c6fe..3cefc25e6 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h @@ -56,7 +56,8 @@ public: qint32 pack(quint8* dataOut); qint32 unpack(const quint8* dataIn); QVariant getValue(quint32 index = 0); - bool setValue(const QVariant& data, quint32 index = 0); + bool checkValue(const QVariant& data, quint32 index = 0); + void setValue(const QVariant& data, quint32 index = 0); double getDouble(quint32 index = 0); void setDouble(double value, quint32 index = 0); quint32 getDataOffset(); diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp index 3733864c2..b082e1eb5 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp @@ -162,19 +162,22 @@ void UAVSettingsImportExportFactory::importUAVSettings() if (uavfield) { QStringList list = f.attribute("values").split(","); if (list.length() == 1) { - if (false == uavfield->setValue(f.attribute("values"))) { - qDebug() << "setValue returned false on: " << uavObjectName << f.attribute("values"); + if (false == uavfield->checkValue(f.attribute("values"))) { + qDebug() << "checkValue returned false on: " << uavObjectName << f.attribute("values"); setError = true; - } + } else + uavfield->setValue(f.attribute("values")); } else { // This is an enum: int i=0; QStringList list = f.attribute("values").split(","); foreach (QString element, list) { - if (false == uavfield->setValue(element,i++)) { - qDebug() << "setValue returned false on: " << uavObjectName << list; + if (false == uavfield->checkValue(element,i)) { + qDebug() << "checkValue(list) returned false on: " << uavObjectName << list; setError = true; - } + } else + uavfield->setValue(element,i); + i++; } } } else { From c9933e78c21f8d2778b7dec831715fae8c317386 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 10 Dec 2011 11:00:10 -0600 Subject: [PATCH 21/24] Update to joystick image for gcs controller to be much prettier. --- .../src/plugins/gcscontrol/gcscontrol.ui | 274 +-- .../plugins/gcscontrol/images/joystick.svg | 2062 +++++++++++++++-- 2 files changed, 2021 insertions(+), 315 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrol.ui b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrol.ui index fdcac0346..f48029e47 100644 --- a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrol.ui +++ b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrol.ui @@ -1,134 +1,140 @@ - - - GCSControl - - - - 0 - 0 - 653 - 295 - - - - - 0 - 0 - - - - Form - - - - 2 - - - 5 - - - - - - - - - GCS Control - - - - - - - Armed - - - - - - - Flight Mode: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - - - - - 10 - - - 0 - - - - - - 0 - 0 - - - - - 100 - 100 - - - - false - - - - - - - - 0 - 0 - - - - - 100 - 100 - - - - - - - - Qt::Vertical - - - - 2 - 40 - - - - - - - - - - - JoystickControl - QWidget -
joystickcontrol.h
- 1 -
-
- - -
+ + + GCSControl + + + + 0 + 0 + 653 + 295 + + + + + 0 + 0 + + + + Form + + + background:transparent + + + + 2 + + + 5 + + + + + + + + + GCS Control + + + + + + + Armed + + + + + + + Flight Mode: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + + + + + 10 + + + 0 + + + + + + 0 + 0 + + + + + 100 + 100 + + + + false + + + background:transparent + + + + + + + Qt::Vertical + + + + 2 + 40 + + + + + + + + + 0 + 0 + + + + + 100 + 100 + + + + + + + + + + + JoystickControl + QWidget +
joystickcontrol.h
+ 1 +
+
+ + +
diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/images/joystick.svg b/ground/openpilotgcs/src/plugins/gcscontrol/images/joystick.svg index 729a48476..386881587 100644 --- a/ground/openpilotgcs/src/plugins/gcscontrol/images/joystick.svg +++ b/ground/openpilotgcs/src/plugins/gcscontrol/images/joystick.svg @@ -1,5 +1,5 @@ - + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - - - - - - - - - + xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAEAAAABACAYAAACqaXHeAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAYeSURB VHja7FuLjts2ECQlSn4k6f9/Z5OzrSdbA2KxmMwuSdlO7poTQEhnnyzPcHa5D9q5z+PPPvw7fl78 PxDwzM+PH4UAX/l3Cdj4KjL8i4Cza7+DgEgAx2cS4V8E3Bdc470ILMJ1KSm/lACvAC8ZGgGxcjxE gn/SrONoyLkxiGDAV3Fe4bV07RR1FB/hSbOOQHG0QEIDBEgAKxkLeY2Zga8lIjwAHmdcgtVGel+S 4BTwS2Z4UAYSEZ9NAAPPgAcyWnFGNSABEuSsjEb8zwr3+xoSwoPgE5gErtuuOzIkIegTIhCQgE7K SO/77f/ddm8DJDxFARZ4OeMJaK8MSYRUgRMA5MzfgY5iDNu53d5jK8oiSHAlRNQoQAOfgB02oPfz cTvLIUlohS/wYP8I/g78tt1/2545iO+SjhnMoMgfhMrljoHvBcg78NM2juKMJEhf4Ij8pw1kAn+/ 9wo+BRWEx1pCQtjp9BB8AnoW4yTOR0FAL0CgAhYx+4mA6zZ6YUKNEsPIOMKXBEmhUPoNgA9C9kcB 9gsMSUZSAfqBdCyCgGmb+ZsgD++zgqgoVBAtfxAqIj0pf5z9O8ivYnwDEk4GEGco4E7AJTP7LHiS KjCDo1Dh+BqwfTn7XwTwv7bzV0FCIqAHAjQTkApg4PEeFj02xP5/UkGoiPOZ4zsK6SMBiYQzIaA1 CJg3BRwM6UcSMc4QRK3EH1SZgDfk34H8JQGoAukDegiGPIkD0ipwAIcpzQXjBRYtrmJJ3LUKOMMB ogLOYP/fhB84g/13xJFFADbB/6GvmJVgadxeCyQocswMQoX8W2X5OwEJuBIw+28UBSQVhAx4XCrT YObiLWcYdjpADH7OyjgR+SMwzAVWkjBp4G8iUOqVUNtbdY+wYwkMIqBJBBwh+juJ17Uv55UgZiEz huBv5PPxGUwFcc8yyBSAKjiQHACToM5IhZ2xdiezOMDqcDDA52b/PzJyJuAKkqAevkivpMAtOFRX kLRIAjojw+zgOa1RglN9gC8MhVkK3GW+EJbIWHU4fTHp9Fql0NIVgm9ydc9QEANoRZCWVHoCKYE1 hkfOZZ5amS0o5TZGcLUTtFTAzIFdNwZ4TXExU2ZnBdbcs7JV72ZHm6u29u8ywGsLsCW9huJyf+P+ 8CNHQDQKDnu7NqU1+z2dIkee/XBRNCpdGZl14bWWn+eaF9HoC5Y2TLRJKFaAxfBKQM+ZlLT0i0UD MOsVLAXPyioiKF6Yzf6aqduPSu0+rRArEB+VslYOOHs2koK9xGoTYAyyuv0ENfsRiOiM2N8rLfGV gJ6M1JeRoKmuKheIpPLCgA9Qwj5Caop5f0vWfGZmk6gOjaRPMADxk6KCaDn3oLzpM7MykpT0uoG/ FhQwG6UgEmHmB/KMq/j7ZpDAVFBtApoCRvhyF6WGh1mdVRBhdcFBAL8IAi5AxLBDBZSAaMwKI+AK LbFcyXs2/MIK5a4RwL+JcRFDI+BhH8Bq7jOZnYvS82PgWVHUE/nLwkcC/+Pf8X07/9hekyYxgjNc lVUglpqA5gMm0aAMRr8OKzlaXdARApJNJ4BvG/jvgoQ3QYJmArHWBHJmMBu7QFjTAk2mN1pj2BgZ gICkgL+FCqQvGAQB66NOEFWwiv57AsXS0FwN71BIAJrYRYBORLyBD0jEWQ4w1qwC2lLYiA0KjVHD QyAH0huwOkOD4gRR/tIJSvuPe02AqUDuuJiVHDwaBFwr2uPSB9yECq6wAjAHyHICt7c5ioVKaQqz siFBA3Eg5XFW91+M2v9VCYRGJRQuyghLFIDyzoXNKGNri0yj9AYx2pThL4bBJdHfbhNg8lkNAhZC gLZJqjVaY1rfbxQOz4r8Vle4e7S0IOINEnIhs7VNrlEIWJy9TU4Cn2vtfq8CNBKi0a+fXH6jpM98 BhsS+LKnElRLgEWClThpW2VZc0RKd1EKIlrZDTdPF9cea/cKs5XBKxnk4so3S7PaIwO6OH33+K6t 8+95u7y2VX7NVIR3A3mEiN/1gwn3CPhnEKB1fV7xkxlnzPZv+8lMjghNJTVNEefe+Y+mSvqJtc/8 kD+be/Xnf5gfTj7redF9Hp/Hy49/BBgApEegBA3kNcsAAAAASUVORK5CYII=" + transform="translate(1,1)" + id="image41" + style="opacity:0.75"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 50 % + + 75 % + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 75 % + + 50 % + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file From 24d6c971e68dc0a512b62dd51627f8ddc18e08bc Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 10 Dec 2011 12:50:30 -0600 Subject: [PATCH 22/24] These layout sizes work on mac too now. --- .../openpilotgcs/src/plugins/config/outputchannelform.h | 4 ++-- .../openpilotgcs/src/plugins/config/outputchannelform.ui | 8 ++++---- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.h b/ground/openpilotgcs/src/plugins/config/outputchannelform.h index e0cae75d2..7d492dc1a 100644 --- a/ground/openpilotgcs/src/plugins/config/outputchannelform.h +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.h @@ -30,7 +30,7 @@ #include #include "ui_outputchannelform.h" -class ConfigInputWidget; +class ConfigOnputWidget; class OutputChannelForm : public QWidget { @@ -39,7 +39,7 @@ class OutputChannelForm : public QWidget public: explicit OutputChannelForm(const int index, QWidget *parent = NULL, const bool showLegend = false); ~OutputChannelForm(); - friend class ConfigInputWidget; + friend class ConfigOnputWidget; void setAssignment(const QString &assignment); int index() const; diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.ui b/ground/openpilotgcs/src/plugins/config/outputchannelform.ui index 4988b5e7d..cb1fd73f2 100644 --- a/ground/openpilotgcs/src/plugins/config/outputchannelform.ui +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.ui @@ -6,8 +6,8 @@ 0 0 - 562 - 49 + 605 + 56 @@ -144,7 +144,7 @@ - 25 + 40 0 @@ -163,7 +163,7 @@ - 25 + 40 0 From 62cf257071e33a08728279761230df95a88b8146 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 10 Dec 2011 14:02:18 -0600 Subject: [PATCH 23/24] Update to OSX packaging to allow 32/64 bit binaries to fit --- package/osx/OpenPilot.dmg | Bin 5526186 -> 5526175 bytes package/osx/package | 6 ++++-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/package/osx/OpenPilot.dmg b/package/osx/OpenPilot.dmg index c8e1056fb343ea44926d32c33291ea1c55353b4a..9d231cdf6b1a25be5f6f30acee1a36743bb1be9f 100644 GIT binary patch delta 15083 zcmc(l1yCH#+V2Ad2@)WpkpcbWb@-qwzYYZv^95=oZt2_YTh5y7sL7i4b4q2SCy58D zm1qHj$79g zcn>|{@zTaMmGObnW(Ss5%iFDI(#!7wd<_fJqXRAJJ0CC7OA6T84o*^nV<^f;w!?>T zbwsF1oN#17aCgT`su-4Q6J^QAaAqVO(i>E?v9u^dy%s-G+not1N@hf=$)hPoy%l1^ zImFWJ@vmv6UhQ`A(Jj{uK9@6Xik@D3hX2-tq+4$WrtM*zsJHFdE5&+Iq`FY#=cKt% z9;kVKR;q8T`KT@I5l4_+ip0xiXa30Y$g#x8#x{vKz^g>i$6Zk#?I^;l>4aC{vI34u z4rS#E>+I`!i1%{Dh;wp@a{y(?f!lFgUGliwcM;27dIEiN@$4ZHw1R{tNrSO+gSowe zN6)ZV%Pr@nXT(sI9bwO)C-994BM-)-(vNH4^d5}`_k+IwdF0Ts-8Lvw#iTptdEv%5v1x__@6s%*_c+l9rjM zbNU*<@>eMK7A6qe{*Mv-8BWqG+=oDWTx(bT`QlfXyA!oaubnAl~NN?@O31n9#u|i-!V`_-`?8zCnPRVOU)hq#KtxQG82Ff zW}t!MC}t~oS>|a%1q04bYpz^!l;#J$F-9!qm2#K(*-+mx$C)bUVJ06IuAkF*=X+L$ zj7UUdG2t0hR$pkjwIC87>sPHRN&Wd+wc5q;PB*k>3eAMhw0ejk^h}lkdTdjX;Sz(z z$1A>~i}gFcGmpYziq`OJPIktD>81B2V(@(M< zCdZ zXS^-YA2a4Nu7aFTSlPFvyMg!#1JZ|kl}h6->Z%^~ZmP%c)03PJtNJ~f00h$ePPX)# zCDPrl)AxrbQL2nAw%pv0_8L1~*8QFu0d1PK>2EQSeyz?#^IRRVk%-j9gF(e*&fNZ? z75(v6thQ#Nwi`k{YHu#Kx9wcMJn7!rVhYLSF2;JRUe@t8@AgX_+IOZrHOBHgQO0xP ziPHngxA|Pg{T9tjpN|*3E&<4jQom*N8e>Ol|a*zGkGelLhMC=JeQxekZ}n#H?; zZ|A8_W$ded->;Kv`-FS_+N!3jI+8Yz4$jKYhL1b_bDQM94lW`o9*7J>7a9Ve3)2~4 zvt9skZ+a{TX};4nGG~4ISr&ccSAA~1U}w^Oxb&@P$Cgg;3^uwX=o?}V+`%%u=G2En zHicW7Hp}rVO_N+$n3LjI5CNq34}8z*)iGg~&q7utgo)D!;gsb^rx2$YaNViaNmtkd zFw#pJ*WM4mi}u>Ts23UUmn-rZk|V=-{=`^VHLN!bX;poTmJP=)+e?u+ zb|=5f46d38Ds4PEwd5G-)x^cWSnpQzd6>Vq+9AfX&`ICO;0Y_!J8j_O(9>DpeOM*7 znb?U#RxpKQ7$FlkndOv5_!KpDmkHbXnD^!{ab9~VYO6rAj|Hk;Uv#UTyT|6k89KRa zsQbruxi_-2nv9gNA0{wuwKBbT7|SV@7gal*3CF58;llQ~Ftp4940k$~Y@hayW7*GMcKK*LS+LGq)s_hlqYjw6I%OxCZ(ve(r&1Skm1Q$@?Psx$d@knI~p|a=%YZ@R&lC%oFQe zHS*_CiJHrwd44k5q}Z<78MNhkme#A*mMCVHXjBfArzTN?2T&Zs^{U5ByV~}Gd?!Jifn!Vs96vPZIqPEFQeUQEg2o)9}u4V zOkbC&-#V0H&^#cv^jpMu<0Nq{jzUoC;vj4w^mgu=uye+;tMyZVa~HOTj&D+YAljjhF}P%{JU6{!&_>m{SG{)_%dQx z1c2Ldq_3@+%QASbpO<$_8@SQKeIf6oKf4J;GPj=mq6oFPdGtY<2*-%1R4W9<>?Ged zbi@mTIA0f&ZVJ{sMVC+AJJiHUTzV;{f2_Wom!Y-+v@qyVa`RCO)W~qPXUn3~k(*C2 z$N2DC;>}Uz`ajO`&(ownukz;@hb#NhzU6h*VDUC+@V19wc)`|?QkDCQq%X5m8eCTX z@1^oz)=kQ)M-asB3-QC-Z|5||^-k}cTFxIIl#6yzTTG1G0oTx3+l-UPP9bxm|V?1&Up2ycf;Vb z^^`A;ar0&?eukFOT!ZJd7^MeWFQ5OFmt4dWnhOl+V#O*V4PMaw=&5pgvv0a)`R9cK zk-pupJci78$6K8CyJyy8VwV2EVEk$4&GU&WuQaLX5MJrLxh16|xwiBr*RfvK&ipi_ z!8(MWF$L9!&svqDTxV+NlQ&BH+b)SxgYApjhJsP{F35w#Mh(4~8rMX=wdtHoGw+RH zb8*)1nM=FAI0#QG=+MK!vHY~SsgObEC=L6`GC{ufJ$A>W>6c>5I1`Zyz)113qxosR z5Y)YK93{vbO>9U0CXZmt>y?GS)vICD0YR%@Z3Ovylh2FGL@C9t(J$MqR}2pe`fHbF zRf#!?vUF3E_Ou4vZGH*9)(h-=ImwIkt@{*1`uS=V^4&^@{Gg=GuQ$@?B~vevhvZ4! z4lmtPkJQ{A%=s^V8$W89I|GQ)F%v(ZaPsl&*wgH_el#cbC%<@1{gFicyDVdlt>k-L)R z4T+SN4*t;{4`A8WOLXT-d7AJRnMnazHO{Lf=y{86 zyM{7$_oq`hQH3j!7xmf^vNkzuOTl;g>#*XTTB(b`5K*q8ln*zCUj{Y00$nTDj}W#g z^JS-$WIyH&otl$KwWpR~g_}_D8q6JJ{Y*4^RgKB8aF_7{_qYvpG>iqx0QC%CG?>aR ziW$?tY|*-vKmR7I5OYZ({?4u^V)bgJFBmp0xU}YUcUo}$TzE+JvUdrVm)8oBSx;yq=K2|vd2b_yh_qigJ>npM+;slTZ3*zfLH3mEd>^2HFUBR)}y zsZYF`%8g#3?j0md(I$?f!WRoZe48kJTo+6VzviX>PP=`KXEJ?_3|W=&JAQ;$wd8bo zbpD%+y8%T#I3Om5GI*45JlRrE*`%_-sZC?%g~nz=bY1Fqg#?vbpL zdz1p&+4!VRy0rzxQD4@+yg$tqrGT2Q^;LRpXBl(j3)MLcKm2{&r*X1$w+*Y!3nk2* zlp3#3mcgfrwKux6gr?K1td6KEyr^ELcqJ>+*Nu4>0z^mF5p@?LO`19q6{+@fdaX!% zGcDK4cAW}kichyc=dg#6e>tcCh1_2{F2Z_5R^&CC27L{i-i&C}Zbd zNgdusPkmo&q}CB32}OL3b4U+$5gzBz$LjQ6hz^2W>pLb7WmpL@bVg|24RP@+r%8TAw6k_i-(EME;AHjq;sT97(UYSRq3DcE!Qm#QOHpoF@_!)p;jY*d1!?+AGCHS zdUtt83VXC<-dx`tao}*EvB-2l3mhO08x22+gQWtsKn?JgeS>6Oblc&K&wJCSd3Wm6 zZI1H@)e0!VG28^QN3U$eSINS_TzdO2ajeh|Bqu8o7y{wU(uaxj2br*-Z8V+38_b6v zGG?uJgE5C;BQY4BK6l}nDh;GA15Oq3o50pk$yF4e;-gUEe%vNF!B}Zepi)sdH`qJv*)wb$hi>bq6@X6w_>3c-{%%mU|TtGq{ zewLsTwL`A{4k5q~Zv=+f9^}c>oR0LQ1eV>LFXv3|CS&H|TOtrm6v?UmBQ|SIr(CX3 z_RLo=K#`+G=)`kRq+?o^kH-!w)$NpKkQ1l%#vm@`33P2s$i5is^;pno`YKuZKYLFX^o_HmW=w`v1G*><&``Il@H&3RlZD-$i5mNM3q8Rnq=S>L!{zoJ};Ff&ys z%|iG)i(Z{MI~B(kR1#;FC6sm)`4^AYSP1SLZKW6W9eGe{0u?$TUo3KM>NFKp{YocJ zwau%UF6ZY22)ZucjEc>xo7%V7xb2}k+p>0*PKs~cOCJO2Eh*I%XdSjb!xJlIg&o`M zo_mBrJ3kWkT*>ST)ULFqCn4n}MZ>B;bBT^LKVm-)P^0}<6=q(lS#!K?CSqOG7MaPz zm!I%RxxG&#_at9daWF{v=o8P+pOz_1WTfim)9Gc!nGBC!W+0IBf2w(2vH0jl$;bzQ zwd%VQkuZyMdVD@-y+!-^K>Zaxb1AHm+?+wnglx)krnqfX^Keq4aghnr!LKRz)U^NX z9aYPJ(O~~B!JdR()N1U&v$q@0KVa+V?zMDlT9YWY^wXuPv-MeM@I#Ga;>%B@_j0Sk z2GHGPpp)M)y&iOZ-KoaT7|Zn?hn?KLnwcK@gjRgk7`uWoKsc`8WY%c&)|T+sl5(kk zO_8r9LdxgcY_%Lx{hh~>2HQu!mDv9z#Gd>oAqMueb}oB$jl#dW2C9!+Of*@Jj20!5o>dn@_gYR+V%9)1G}qq5uTb z_J?CsBRjvi-pdHE;MB>XRDUQPzBfQ6<~5D&iB)N$HkVtCOBmd8cvLrl7O~lj#+-geqjiK;CZz zu|Xv(@2xG+G1Cz9p2Z7dlCbCHIGH*!nsO=Orjzn;L$*4uh){AJJVSnd^@@{9912U* z<1!?CXxX0Rf{SCQO%vpnK>zu6mO|!CcAMH~7E0|TV}uTfH!<)q{uuV9zvyp$4ntb< zKTuIEyT&o}llPOn4*DXI!9oq?<=GhB27YbDwCpVsT^`i>JMy0Pa_<#nEH7I^11S805s zeHvOtxq0(LEb)5aO}@-% z`5pc!md|{U#}2>eMB8W#RVqGsz^0`Ai)Otmu*J_)Kr^_ZgFxI-KrTaEk!Xt$OWgN( z&hZ69^{)I{RPqdd0{(7+aQV6j%?=Quedm5Jk&xRscT|XM2T+|EJC`v{1%$fMtlvRvLkNC5nl#7~4 zEures(u|!POZ^O83CU)uPE53DBuNSAcz`xykV6784Gy*SH@|k}Z=I&Vg|m&@C!QY| zWP`SSddVqJ4=QiUI$i;KZ^jYwnJ1}4&d9OX=NFsTZa4J)ahDrc)XlYDReg$^l9~ua z{6v*Sd@|1$;_5dWyX(c>$);+5GM}ne0o%>lXX2+ON!0oe zGBAr{u!I88vhnZwD|nc{={t{xQ7mqV_Q_lx4k0KHgO4;WKuHv|8?{PZJ*Bt_P>0IG z0Q`3hC2wCO%}uOp`Nra6y2(n3Uks4s=IzZNxsmQnGK9W1QY~gj-Ixxy;QB#DW@xd- z+^KHE%8p~#A?@n^&DSQ2y?fMSMr-yeMo*(@Ev0_MX})~-jP7Z8K5X`NKxtDQtsX?6 zyabbIPb2dukjJaCA+`mK4Wv19ccjwbqGpd9QsKArNszQW7OH$JS3(&4nYo5n3|I(P^BvXO)lYmn*+Gv1xEr2KwA9*lqZrV{fvd5OaLib3L)k}POU-~l zC5q9Km*R-BAK9aSScTO;GTS0Vd_k$TCZ-!FoR6fMVmmKbyj=XPveSELBm&=eY$jPQ zJwH)^B<9#zFS#U#0JMF){HN{Xr_jf?w;aeKjurb97b)(?cR{sVTmYZeR;tkK_1n7? z_Xmtvza*Q9*FWQ{Ry4jqs$ochPafo|JN5Lj`MyS0imCs_&9Cr?Ll4=?XCt%)d)iC^7yrlAma`lfmePRSI09 z$*5Gsq;6smx6*-O5*_oHVmwft6Ui*g^>BgfC3zi=iCYeydT3@1UMg9v@y0K^S3rFo zk*M>|Xk+#Kz6;L%a+%w05WxFQ{(W2ms+E*q9=2lxW|T+=Rj@ajf*<9=1=n%5eUrke zkWQ_NDA7~YXX%7YJcER@8Waeo)q}AdU(Ywxdg$bPEE?F8BymW!Ev~D?BX*-EWRE|y z%PvMV5#9xQtJ$dcWSu@gga*C8!)U%-Ov^Mlr*AlmJ$rqI;1I;8E5l~D^+K{3b_-iL zay%dE;di{8-*=R(5QME#@IF+A96n7;s^p+fa%RP_4WfNGaf4~Reo668iE4W629x+B zPdkfsv3RN2G`JoPI$lw{w_ch*Uok+y{djOuaB#N)#MVtO#=-WsbqmNg4=$!={Hz3r zhJ8*lJP61(*^?JsT@%-C7GM=Z!|4oIKMy8I3>Aymv#kDMX_cTnx}p$npD1=JfdyrH z>zzlF*54spu^3!L*SLl|cUInYQ!t3AlvnW{Us0&7jw8uD?aN|dAa`5g-uDIkx`hhZ{C3ybTuS<3uz z>0w6k`p5Kd%c0ymDi}6cS-w~=Ta|zwjK|cCk~t%vDPq{wS9N6cDzeD2sWymorJ9Zl zuCbRQ#893?rqU|FH7@5euwPBwre-|sp@${Gwqm2{@Hf%oAC*0M#@h3>86NqB7F)9@ zp!-3z&?uB;yI$IEb|_R?C|^aQxM;aqkbZA9fxp~J5?0v% z*X{H^OSh?h&3^B$rKe2;GWK=1>)U@>)|O?B$G*{)L0dF7*ZC<8py)Y?QtSb~nDW=y zd)Wz(=HS&_==BouY;Yibc$=En$ohNr7il!Z4A*kco7}n;^Welh82T&H zNoJ@wxoJoEW6L(?J$70maSpJpl^uOfY5Y{r?Br$S0K=8pdi8ci<)rx!HP?2H*xh~_ zcb6&EKWz0P*8y;=K>2@wrITr5|g73a*xbEt_>u%u1avHN{wVoO25kMS65o zJ>I!k!}i*FN%{?RH6I7-Kuh_xnao}aUY#vMnIS#7r!$(eV8!#O6#Vr=v5+E}V(+JB zll?-bfRoy8Yx`uZtC$m@IqO1R*s5c>s3hzjqN3t>J@X{1+@Tom%ejhCtt~+U;LuJSV>juH*QdU;{pmwl-D2XP)e=0VFiKGrYA7@ zl}QU@NlF~72lN>(&!Ge*icPy^}s#)}=+yyaiuI6KLSbSpq7r|v0gnf!F#I|qcc}a7$ zhxmqFU45!5?{@=~VM;=;a3e0gKWneeHscd3dab-v%}qni)~-Q!6#bT}dbxK5-1{}q zh#;$P`IOPlG+LUYZ!U0{FoNFGMlKMBi zyMwg)SB+o1Sx8ZyJZ|tf$HmvQS9+?tzhOl~cy|dpI0}H)JCgIVaXAa6xb0`KaqgX$ z=Lteuy^Th)w@p8)x98~McuuYGFxvhy!otzT`#gl_{BPI&-8-O3`9)SB?w5lz@t=r! zVoI-?*;FLb>+952WA-zSv}(znSo*P7ks6x6kcm+_Cg1V>^hz=wQe5`-OS1O9-%8>F z%S^Nt3stjj#q>V}w-@&pmopJU@3alB4M_|!8>|}V%iONiZeKO4I*r+##9XO=)yXO| zE;k-~Y&UExKJwN^qgv#d4Z*{c#q&3tozE-r0yf7jua_`%_-B5>diey%luKcudV7sn zT3xN^I&a*O2Lv}6SWZb(O*PUAVpn%PfsRMn(*@T94)@NHoIu$`p_EIs5!F`$fp(rE z>6ayNw~9qs4;WvHC%6&2?|YL3AX*^vmBaO3;AnJ(Xv?wlNmWb#MChMyrp@%yZQ8MYsAwEZ4Q%ND`kpjTw=sZDAKhhcgW=PF$TluNB{%_PtT3pyZZrnu}2So6RB>g5f@yoCK1-$=*?40MgSGjYO})`QZE!vKRmqF&G{ z@w2JwURb>_E*X2%W}4Poqnynf-2BX_F~3!iLhGTwsId-l40<*3{)PCgsZfmhE{f?f z_NtS;M9j1R(f-G}F6IZ;up%mFU1{qZQmVk)(j|zyQ#5Jgx|@4E36f~#xx>}|c-4N* zxiLGd-{>||nDwyr`FwvAye-#X`+W>RJM&fPOFlK(tZwWZG%=1F zw}x*|d$0q;+#EBX4G#fx=Oli`c-&T(24@+^HG)5qPGO}Dt>knZ^N&>W&<)UbV0#8J zllvw(<(|;RE8rY9!*F(~13M7B_u&vB2zuX&TbmwU0ndpyP<0W_c&*X^&_>8@$I)n3 zBic<{4x{&B>6*{5r5ox@Wv(GEvB_7nlT&Ehft6NlDCcWS8Nr5qpcr4WreVq|GyV-n zSHPRgL$yCrxh@Rlr1{SHcc{rH2G+uCUawQ{?)0PyB|3rXW?s_hn}W2y-okn24ulMg zDCpuv5305S3UENti%b*8;56;uo z*|l{;9zpgb@_*-w;An4;3-P{qALG>6@a7l(2DslWbHVC7Z3P^MC{|Korh|aL_i^>w z&8|~p^ZGjqvvY?GG0!1PVr&v1_q$-0OlL0U&DW)b#Z(t|5ubHllZ(hCQxb-x5gcS7 zOdKxPYboZ4Lif-wXV?Xc4L|f%Z)jpyGI>j(8C~o%oLWf=Ur@cxVfUI3NJQgBC{Kf~ ziD=zbt(%YignJP=xVWy%L$4lcAj%2V&E;gMQ%1_($5K3C-4inC92@ieisXPl_%h*f z^cg3gpp?j%f^fxH2YRiOb#xzd%x3@#ElW~Ixi{y)TYGtzR?#Al0Y2O#yAqzK#~1-1 zo42jdV>+ED%mOY-X~u*H1P`Qs1P{;sSk^P`o7&%H`r@8d^$=%v_)sZkNg>TxsUs}9}Yg0*o3*lJj!Im_`Pd_ud1b%!Lz5dm~7pD@vi9eZ~y7PD7JV~9>?hc z4J=oPWEdWUgKYv|Ym0$Oa!w+U@Okd2Ecj@M{`PsX1xNnw)t>x&<%WfqArgPoTYnxW zvM?aQCAM+SpD~={y?JI^ph^8WVpxnO<3H;+bZ)WjosdELSbB-l@yGAt1U8m`y_7rR zd}tp2F9Bg`ve{JE!wKdIw=1GKy*VFCx|UzJs+ym0!nm%gmD2G4wqO%t(;gi~$Xb^pP&BZbpeTZ*hTZv)!i#+fAE#?kO#Uc3c z;w7;#5d+yuI-<3lMU;wz_W6iZHB?<=-xMz1LOj*#6=^UXU;Wq-_okF!9f&O!$Mzq^wG@U&&-tTHFG{}&_%~)gpI{>uf}4 zU90nS)3K!Bh)*wx#)8jEfj}n`tG|Qz2+PX;lkDt7wmm8qAgC0FkrafBqi>M^a7Z?@ z=gbaZ)~;$GDE9Q(N|>V&}q( zn2|LyyXRx1-g$Iwzr;rx2!a+Q;JhBt;db^BRip{Pf^%R;P6zL=483mSmOQ6nhqs;2 zw3o1x9qag`!w`-H>+s^4g9L7^$M^t*Eo{ zeMrW-dK)x_GAa9+m!s4}spg}1H?tenx~-*`!3$R#iuOS;ei6S;&&Nfv`jfL!nh?}t zrykZV2Si*-vG_j@tRphBnN%~R)pMEvBe$}5l_b~P+5ZGR44k$ePxn)AG_7D{YiAXMw3{%`pm&`deYwO-CsVya;ajR04H;S(x~#~ z^!yJG&!36yXSm@7wTjUm+AY^spwm9>61JN7|f;&H=j~<7k>T?PQ*JdEqC0@E4@N{C9 z(?5lL2g6QBY-fkwKgv4&7t7`Dz2(v*mAfQ*12wn4{pz2V%Ujjql7gqlvkhAQm>wya zm0E*tUn8%4dS6b~4Em~H$nWasVARk29p%V@{^+6E-CDD;PsZ0Ik%pZnyC5J?PM9i? z>Pv(I`$`*s?}MB!g>@q;a&KJLMb&ljyc?)Hne5tv_w@EHkkk#xw6WuK z1KBplPd<3B4D@b~qrE8{P>hCw3am1C)hT^1&?dxOL?K`^2oW^5!Ccerirkud%9Z2> zs)%8SP3{Ma1O*RcPCiK4llW}50&!rhqw>qM=fyb@J6|hS8dWi2?Dp>vK(_)l=pe%Y zf>m3$V!TM!#5qvgJ+Qj7+cA^S^5Ymq12sBTNWsvcV5EH(;@TCVWc6sGh)Q@D#(USq zz_)?q+Q^?=a>8Z|h@qr)+>~vQpoGU|XU+0Lbw=$d$iL-R;ojxF)8#(u=-C&d+^zV# zQk@HQDSf5Ky=ITEE)^4d6rzEN!cLS-q{FhLJK~F-JaP{>_gTgAg(*zOST9nMe0zP$ z#Zjv*0sWA%>F`NZ8-J{{(UFYBB7=JI6OzBAS2&wb@C=F_&g|b|!B4(ZkG&2k9?DD2 z_mLC$6Bew|q$2)W*7Cg~&qlHJKNVLIu%l}+R?fWteXv0to$ILrCMfBA)xV_eMj_ z%_;PKB>j&;0XYwym;nZfx|&t0yw?8`yG?2S$UaJhFbzu(2UsLAdcyYjx;Q~rLQqs)7Zk6yghuq=+^!j^W4||7GfxmPz>5xi~+CD zs5zkJK5)QZ!Z9qBF$;a}owX>;`w|=8mRe~5suVn7~XXI}-Yf~AdpTc6T18$wkqP@g^dg(n4^%3{F zH3I`_7xsCiUUj}6Ue;Dglxu{COFZIi(VO#s+$jvyYJ+ArR|)?!B0)rGs8^e~KWJUE zaS)S#(f?0(pEVepw&ZRv=Heey<}nxa3%i@tUu=*;EX-sVT)h4Y$q$zQHw6~ZW{q(7 zv^kZ38@p`04594Wpmv*LOMHCi#I@9rrG_1x4bIh+l+yh_7`?n)d@sWiwEhB>n56gxR6+z24`ZeQjs%@?-$*&q4}ZI& z4zDnK`@X%?ZfPuw@>LpnI}Ipw9Y%=^?}*cWd^t6~PvcPna2vte9wG0;5Y|V7;;XQD z6*W;fBIQlPtJM;dOe3=t2ZUd*xVh&WO8v@;%asCLVGB1uhMg+J#nq{UtPs`b)Ayd4 zKP*C-2Ph~t?$r9O59jxrj?-ApPTvrs$+skb{yxE0hF*v+DVc=rfDnQZfe?d`fRKWafslhxfKY-^fl!0cfY5?G1)&3>2VnqV1YrVU24MkV z1z`hW2jKwW1mObV2H^qW1>pnX2N3`f1Q7xe1`z=f1rY-g2ay1g1d#%f29W`g1(5@h z2T=e~1W^J}22lZd2J#$4732ko8i;!BX_SU(Cg7+1%04XVoR1NK(SdTq!UW62#3T@| zgWr*Zql4ViOg6v|g#k{0+63X!mq&}^O}hakE1 zJ`_PhN3SvY8Xjc9jTLNj3>WG1&g~VFnoTDBKtTAbpbaD*Oa;ux4<2BJk{gPMdpp=u zdRo@bFhMTi(Df9Q-1NLOBqb$fc%TVf5E?2OH3eV$m+agEl9IAEoG*BE*sZ+4EC;8w zgO9w8t(6*-iWNdDDXpmVcQZLjYgKI(cGO4U=e{k6lmM@;ryx7nC%>gFv)u2#BsC=2 z*}*=+&r4}@upS!53Q>f!f{w64*xJAA}lS#|tXX2iB=TefS_^a5B(3K8O&U8uZtFp)!<}|971=n7}``gMQ!#+xS3N z?n_;uBm!Wmyc1MQ03rY{!wZcU0Bc`DhXueM%*DUJz^yxvwFE;t4@W;d!j@heZZ`0Up4~-k**KWs-uRLt}*?gm9A30wM56ZJ{ed z;1zlE+}8_&e=c}FDRh_{f&>i^{(Z$MU^)D=-_s@tXL>(lV(@&wub32S1vZ9vwEoAG zQNk(Q&z2yZJ@i5ZA`YkdXV99W;0QSW3@r}K!>f7yW5&>+L!#ht6rr1<;CWV1Dlzaf z6rd(z;6>@)PctdBRt!Q0{y&pqU;_mxrZ_kr@NZHQ2OD}r-++g3($IEsu>CXW-Tjdj zR6yeQ#Cb`8O*QTQ^fDv?_M!yc1EQ* zVCVV!M74k8VQASEaXeIpMsh5LW~>PuFDh+???~oBUycZt{r>z_&+*rx1c{&-46J{%85eq={@w2H^Ee*R{b~6hJG`%k hFm*yB)gTcMBi4;X?ne#a-4Eiy0}2VH-|1gp{|le=gpvRN delta 15064 zcmc(_by!tR+xPDVrKG!4K|s1&I+faVgLH{V$D+GIHX$G-C?(yXGzfxpcOxa8`?t{R zy081b-{<$&`yR)$kK?mv&8%57v)7tE^Ihk8X664t_yhvDL!2>8O^p|g7CYI|WL~1& zyGPXpNpy$o4s)QjvEw5xhNUZ(Em8>kHQ*CvFG3W)(n=TQpFX1;gNhUBO<*nrKJ}27 zYZ03gJ?4ouBkcB^;f7UYkrZl)IY!hJHEg>M?BrZjzouZg;u`CCP~mu+9w*#Z-jD^; zFnEU~`c>!=+`yCAOH0@iug%6Te4hKh=mkS8v5xk2A$z>u7gaV+84KE1huJ{?q@<8Bzm_0UiYA80jJodZ9fgX;~HFnV&)1x6zc3-I# z8Uf0-^OqGmKNC?P6=X9heiOVxB*BNAhOvA)+5r^gwkB|+F&}xGkByHXRxcKbx)kj- zYq+#tYRt{lI{0WjzE4K~<$kFKg84<;+@ltzJ_Y7|Bt#KlzJ7i6M}9_02i^R|uZhLg zcBCNU$3d=;)BY<7;a5^t{0f?NqWEoR0vE>meOt};sl2x%ktNFHDwdgncyx}~uw!PJ zE3%cuNKjpFI4xCx&*&>_!1#lnr~jN>&@e?Es`T@VX-Ek^>R0pj`ziPEj1iRlP}w1O zV-fcM76|ZY8Llq1n7UH+uwv92d*9&5z8^gO74{AFVgLP*%xCFCp|`Z&59nX<;2fOz znpkuGny{$DgIk4eamJL>1@(5H>$Aky*+I2NEx&R0Kc*AA!m32~_5ho2!AAHv_Zn4a9`HqUt>rC{vMG(j->HOlh^)ymGL_95|1ciN-1@R_4-xhWInva5qZfd^<1d`6)~TN6u-6$yJoY9xAKQm^{0xfH)l2 zVr+t$#n5yb3-Y8VUtcaef=zxfK6Yxe>UI5fNG$6+WO z3q4}X8p2$D=Q77MuW}OPw38xF7F8LTI+#?MxA4Qv4<-b9eoBaJvH#SmvwSN|n0mYu zaphWBn&gMR)zvgxrE3CUlDl0e&2n>jd~){T6ZbI{O8F+OjOv#G>_GiS!@#EswbI>G z@{BgBA}QWP-rHXzB${Hd9TK$XqaRS~GbVrG%~?-1S+*dKk6dCH@x1vEImNFTwu?Rr zRXD-mLQgnbpoVPUdaX zrCa{2t;$5}L!IPaZ-51M;XBjk247PTWG;#0h$+A}6WlA(c`~Ad@-5`gL{0gk@nZ3? zCoo<?^kdc`cHeki zKfD&W#cS#IKJvy{5SlM&=9y=lf0)^vnV%^f3)BMDtwU-=N709rCpGS5%|{|et~-|k zyD9D(Rm*S@dRiDytX=xgQqPLg0?uFiL-TA+6JKJMTBUg=#-2Ou$^xA=#fklxBrwS}6TJZ@cm?p8oQL$Tsy z7EVXkfv`CviX}FS&H=R$>?^LtERmLqYS-U0KP)BkHJuES>c8$#Qf}QNue4f8=~j^U$$r7{?ry5F(BnZ2n&bIX!Z z|Eb88Y%%YqyHfZ1c)9vOJ3%9i*!Lzy{~aC6PlR&ad9IT>+fVO1Z6{(>>oh5+IzDpu zwioT}*l3M&uWCKQ9K9*za7RH-H{P13=i};sjxE_8mXs-+{Qk{$Ugj|_p!m%rI&j#k zQVQ2HSDx}kWP-+G1@{)C)mxioTm7%Ot|j%#HUWHLZwuQoLV_MyV!F@zZNNROm$Zg^ zuaM`LzfEdignvx*aojSJLykib)|tq5b%<-&a9c8@**!)`8hBlY;p$;Evyx$trB_q5 zadRcdtfq8xsaC;|$$h_r7$}UGS>o%GAdw9nN%f1|p}l`|D>Z%ff>m!h19|%C%-i#Y zG7IUOORtCsX1;<11~9CX{Dq_RM&J?bd032QpueAyF=#jP94a+lFaTeH#NlYUo< zcCyKpkk0f;R^9yjUDs!7)quuspA3`vm3Xd%K+QNsKwZ`FLlSZ?KVaUGd}H;Ho6pl9 z$A9>0{QWRjmW+rjt`2U4VY~Wf!pJAvbm53$s?=l)2Lb-Oje&XurRt^m8j{g*?Zv5Q zt!H=rV58`(w_E#GyTp*8M>9tba^8s3aPc~;Xxo{k;quY>?k8QWTu3qor+hIfZNuq7 zN)#rtX8m;0PI=?1K=ZLWbF}Vhwfl;?Su7*wO>L?ZZuIO2_CdNRf#o-E0``eioft}0 z!rzRY%U|8bt=Aahap(g`K?B%y-)vk;L@~-Ox&M3lBuFf# z?1#j;hSvQ>j73A3Bx}wnYjh>J9)4?qshF=GQ^~ZBOgyecx7(9#ao^M2LGVaB;m@o6 zl}vJ=g9dJ9|FLm$raycB>K$BiVbDkHSmT`j{M2jz;I_{>)UwqpW+r3j*N#_}{j>t$ zq)JXWm~9_^2=Br00S0BSsO(ud9%#xoHl67ki_8puDhVh#ZOS!IlDzpQhiKuq`&m9L z&F=eSFN>1egEcQ!yKw8Z{1RKYeMGg51iSVEz&7YS1N+P|h{_=(#X3%s$fzQ3tE@oh zglWd7&#Zr5aim&}CYG|j%K@O@Rqp~O&~=RZ_obS>V2mAB+FVkfZc6YS(Tguw7&2zn z^wX?|qJ&cB-4z}#+%K+r5<2H4VLjhK{w^z6pyvbGPvNj3|9zZIyg8SG3Zd_Gx683#Z-|j^B!jr=A05QxauRX7${$4X!aTd3Kw#C zr!0(P^?5THGAJE-=TrBV8JfTNAwF8+dg%R$VQGbJfoL+j4>tFM#5>53i_yF(W8uEP@Rnl3yxEpTWZFLZB8uz*6C z%BlbBhB94LY#QRw`Vntt41BBx7##MFOUhUNoULP-ZiUQCv9fsdr51-{?tDw1x%uVFyM_|IJp=--=d*D*Sr{*-liZH&yd&vP;RTa?Gl^1mPY;wkU zbE!d=sT;vBQ-ZZAKD^=osafKw%tHz|T3mDT3qpD{=}PN+o6yKm3Um#J`T$Q!&Jz2_0qcxNI)k3~}+S zD{LFZa)v}c;#+|lT0afZK7QJ!r-0eJg6V`3wIJ_gh@m(F{SSRd#hFa+aLL7B{Q%(R z4M3MMgT{?BM)&ogn~kRm_H#-c#c&(z%jQmw+Q&rCy;pfT70W=#{DXzIWKvnn%(^As zr=!T-;@)BOrsSfOdB&FGJYi$$|E%Mb7>5Hv%^35Di?T8%Da>QpqM!29I&MiYAhQSI7QbP<_^i6!5;u8WKK2|pOStlxxX}1ZkMl0)CyzAXIV)V zbSoIWPwjiJI2lI`nx}U!8^0GVx`;0;@yK+Ew3cmN?TYP>O@Q-PR*HpBS1~9CY`*Kh zdkb@+ai^|h;pcN_9Kx9-O`&*&9CLMcPIT^k&EOq-v3^0@;?|_>W!t0`9FQ`zYuqp>9k*PA_*~nx+e_dlWr@j$dPFXO<8H5jE zM9(@MEL~7}uHd8!!Q1U$%FUedJ-WJzIe9#NLKdYavk+si;akG?<5x!qgRTwIX!UGwRC_P4vBt@oHzX#`!`BkY(6l6wAelGhm z+>dfRmNgB~O*dg}H51SYK71;iSdNDe_~+fPU^68Md;akHULae=9G+Hh4=TX&Vg0Zj5=FYT7SXrc<)i`Tl%);w> z391s@dIl^Xy`x8pgHzoeU| z1ch#77;z{kbFPO7#!T_c+Lq*6Q=_-+!W=G~y{<7jRj;~@B#ejHLg_1X(ByNl)~t*3 zP#JN{lHR`#muHh^O;K_^rWVeY;!MS_Hd!#u`F>Ivz4VS1sd71}S+iT)BlL%X#iYZ; zSmcE1Lc-H6T?&93V74|P3LE>C`LWwTJ$TIM=QIb}L@(XUuHg8K#N(3EvLXYWk+`g3 zS+3Cerw&@pe>tB1$$*bvWy8UuN?~-U3 zl6Oy8Qy1=r*rftBqZnVCENcIuaWE#{IM0M-@6}YfYx3%q%-9w|z_LOQ#DCuJn1W`VInHx4|q5Ye#plxnk4Nvvl(-ZJN6OmSX_AvlQ%q z(qm;AszjQ*ZlD-T;rI|g-{Jb>=@|QZD@^yo=D*e0=!zs#H|6^?vTgwn;elvFW2yJY zEj)$C{ROIn@lwe_r4t8_8dj^er|DyJj%7dOr|MyTzx(U;2v?s1>g-y%kT$3Jd)xFM+Bgd80}Hvyb~8jZ#v=&RRrV2|72a`K-&E18^Wowt}g^k{#viq~e ze2JE`;XD>&cQsH77zoys!|+TR)wgunG_&#Z?Ht&QpYfajK;VwZweYpHoru;FtKr%v zh>bi@r(I~UhnSM{p?o^EGbOK~oa92=tXkX4q$k`Y))s|B;U`?!GBe94BX0YY!H+U9 zxT;?^uqV!wl51I9Rf z;k5KL=hVkOn^!}M)z+#%cMLxMgA5p{kwHaChaKSibjgj%`C+GNcjU+UB{(h3wHN>+Ztw!mY`zb+>P?5g$H* zV4HHoZe@lFnJQA|a$~cq{&SL!);&kWnd_JXIO?S`mm$d^AHHQ``~y}X-y!|tcZ#QUCo`&Dv~ zuBLQK>l_Nfgpet~I!L-HIO}Vc!!Cv%Tom3hi>Tgx*2sh1Cm6_CA|##N*ijUJ@6TFT{~<5aD$@cY5pR!L z@aAD6%APhNZjEg9GjlVu%mx{ktR_CCyw7Vc7>^vP;9H=WFDwnLQbs;3O}l1EG9_1F z47o6r;fTq@Z}(QG(V0wKdP)G)F`)=kda!dczNT;DYvR_&Jq^VQtqJOrm>>F4yk6X? z?0ufJbz3KC1db=wN5IS!7W?Puo`N2kcWht^>;%Ru(3V07uDTBMLAfj19-&HX_V(jOAar0Jl| z1NyhkgXdTxnO+2=MD4kEG_(6CxX*TTPvWlobz_X*AhssFm=`-BH0lDn&?wXyuI7hZ z6ELYCm_m9ca`eZSQC*4pj42fI@0nMUI|Ld~PM^A4&a@}*PS3C0`sDrlCaa|Pdy}2{ zw@vo-OO29M)nJAjrrv+;v4?Dh9lTk#5sCv5mnUcV1X>O+9xLx96Vd_1w-}Ny-Y>F!NQuA|6D(W_ECILm&YPB7r3}4T{5C^kinWoI%X~T>^0lr zaxSsD$)RNweW1F5mlu#aL}?w6zSmBR<HiMO|4YTq2P^ z1noJO%;|XdGh+KlI;DkX5B!QL9M06ehXEBP|JdCBWpXcy|5D$RICc9IOO5V|_9VXP zr(!%G9b0fKks)~+?k~$`vTJGM0wCAX->rsW;^t#%b5V1lkC9&CbAtG9q=L|)ZTKSK z)-nNZqXT-PwT*h%c6(x1-RSMO1m5zA2V_hMAkU2$l-YLsF596#*XZTorYqcNB=*T3FVspH&lVlzy($N0wK&y
te)e#^^$eV+VGV#e98}lQ=}d@u}==Ik#p46h8?kYkvg-(1Q#oajO`kk?OI}w= z{q;?n5nj^rh+`g)UbuzTI{??v`7*#M6>OB^pCnlnbfN6`drSR1=OrW-{O}2NP%H|Fc)m zzur7OGO=c3>xt?Z>cn1Cj8jdBd=qwaZ}~ZX;ylf9_{pmC$`+m32L%w{DcQ)qQQlv& z63e0B78KW`2GxmT1+IMnQ~h$24cxd$gi6eLRmXgxKiqAXKb+gRpI2Pf(>}mD>{BFL z?;|Vq5Vt*rc(xoX*yzfx7hS3HZq1Wv)YT#h#VFC|@g$N)#qTsJcxybPgcTgznc{pr zf@0`7-D_ct-`u=-TBFUb@RCO+k?R6 z%E5d0SR?lWfYk$zR^DmvnD@z9ucyBrIr+4IwN#clC!_hMrF2*;}b)_GO? zCE%`XrD9VkP{dfr&OXyRwu8|i=1MUJd~zITuriqTEm2L+HDF6KzcRAGD%%>p95(6A zKuyOgipCYJ2C%-iASiN~HDSPX?f&Oi@rcMF&kwi2HXptW9Kbhx{%H6C?-g7Fpxi>+ ztSD%_B@UaVdad_7lMN>tX_GB%hAEeqym!L_c`K8yT!H30mF94IOJM-D`d zy10R_)&pwt@1p5F_*oQ^X%nA5_w>}sPdg{oIw&--ZLmdQM72&wq~u$?^*6+RdaWS% z@i~Iyp}Af0b;oFLOYL!49-^GTwjYBROXjX^cKjQn%v0{PkM}$^zAf=mM_nW>Py+jQ zUXvAZ;*TAyE2~V!PIkWaC<}iaet#HCP}}Yp70nrgS-=G$n#j)5cvO98^B8M5RPXTx zf4v>(tF@|pdi&t*k%s!i#sA*^D zh#p>Gy>a;UO#qeL(eW3$W1>Gg0iYjzzs9S^-QgriSaxn^j%?03dkFr?w$(OqM|^@D zHskU_>=V_{+17w(MvJ`B2iPXp$>TZDF{FUfoz$9Z$_P+NA zJ9r~x2g&PJYznEs?BhwRN|6syTOV->ggJiCPhf*QI6o7S%Z}-2RQ26l48RXLzC3V3M@Tfs2$?F$^r4;+`%lv*WuJcfn0Csoo zkQ2M@hM)#DDYa|6UdrKhdb*k#E3<&YTypdH+)Y?@mgi=UMi zrymc2jz#*iIkm-iu}=_M=GmS;mqD6FcUz{~WjE;Ja1CO=Ksn^&egDDs9lD#k{tAI# zB`}6vSDek|TZ-L!xn9QX#VZpt_e(&q2O}_Z@`@MONNw}lz2WQYGpcBaSeiPT5;^;o z14&CPXD3a3kB*w?$AS!6zL9`0ZyAhjc`$}7w~_UQSa;w?Lgpf)0=pkybB#`{9H)Mf zqyKUVr>j5KJ~g2Mj}W`&EjpugL}51{yzMbBUfuvjte-?T{X4OKI z9Yu5bwYLj5Vw@2^ka4&dr7yVCc8Oye!UuJTn{KlbL+T|o{k5ZY0D3;-wSK|=Qf=Eo zj@})(Jf$N0*@v`nXVi6tk_XJX)}v`SY6q9V*tqw{V}+g_xWIlz_UX|j5RRIz%x4H^ zUAn;o~SK1v8 zlTqm`MLYzSZV)ewS8>*MTmJD+$b$X}&Zf5sf_#4VR%zJ(>7S^&yq7QZ3NJ!JRGVfx zeht)Ddk5*?NG;sYv$3&S8@DL5u$<<*uCb^FxG;0-D9>YAE^^6_#ELJ@VqavszRNmd znc&MflKk0Xf5hneBu%*UIIBOXdCHa zFh1UE5UZc~z|k2sGaUbyRNN1=>l^%bghqy{a#9NEoehv!$PjKFvqT10_RqZ$tC@RjJ2v+HE7f1`T{|Pve!`uC$ zfX6j^o8iP%#trmIJoO|rVR;;SyJFy9ss1SbM-DOhc%TfARa`6PEvV~^tChB^^@6IB z-8a6f_thXTXY3B0(3s)S&QV6j3BR?=B?yY5HVZDCM7s0TTV#Ah#8@7=M;mR5SN!}X z-xGYD)0OZ}1=mP9=F<^6+753z_&?T|@IF8gk8rJ!W2}&oppc4tI-5h>U@F*i*krQu z)gY6{Q_igkg0o!<14anRaP)7F1oX}$G5e#O_=R%GYqUc_i5>l1h|(8kgyzhoo#JkXA`(xn^#FLW$z= z@H>Vf+MD||NEXPm{wud4w-0W~;iwB{Egmgl`xN^l^Q8Ou`ws>U2i24_HxSRv_8#n^ z?#1edx(vDwat=~tvNgKgymM7*V$%IV85NH5W&U1z>?uIZIvs0;9Q|U5Ff2moM?$ew z`g^q9pc9!Z+-aW7P8S{3DpH}HKO?-mJjEU&xampSP_&Z*_+vPCWt8!1g(BWR6sT;sIv&z8ZA`%f7cb|>R{=@4lY4IuZ!b z_5H^V1$s*_1x=2^S5QBH2aQv*WSHm__`cdgYjnZH%lVfAG6nsKPmm+Y|+Vj?_zybEn^?!+H94)3#3AtKB(^~hCX)VwG%DoRoEPD5V?Pa_H-cX zfLGt9Jlg6=H1A9^YV+ymgT$|R1c{HBNP!#$ZIN1zPt@`Q&#YvRsL!Bmpx$+C{V zB~q}y~Mhmf*Y6DxP@h)ogJ)7PUE2hhiPDZk>GgIPcoceY`MHy_dpY_s9^0uG> zw6f0;Biq$VJZTv@xWrOz`w)wAZ z$1)cxO}QK=-V~fC66fGe;vvV&y}l->oxc$mg&W+ZA2>dXEf{X`QR=smKn}mRp2y~^ zNBz4w)3@&$%l*4%tOjD@rc!83NF<&T*>*^#l$%iWeZVwV_d91+@w5XK5}v^#)8kjH zzh2geUA6bL$oV{CyHZ;n=uuqS4<-uz5Ol4xj|AXMZY^x;EoSWYx&WVS_ifm07A6R7 z)TLJ|ka&EmE`=7Zs2IFlWhh(MoEsY-e7)U6BM zE8k!(7|p&pnS;Ee`(ulEphTDDHw+KM)P%2)GxB{o7SN+BgX26F-F*iAq(4pJ>#P$v z-d!Tm#BnubbTSI(hup-rd0~*0Uw`XTPu%b1rtbT4q+DIOM{(hHZ{sh6d=G=)_v_x# z?AQ}A$yYg_(@-K`7t`rP6Fg@AjBC!K3A5`+6_PG5AA7m|x4qIT zENKL-G`UZ%^+)Kh)f2S{YE9YQ=F*a3?VM^y=f*ON#+4@A-j`~lAwC4U8JhrEyS0J$ zgNdhj`E`!JoRBq)^T#zzbM>dHNv|GH0!7_EHRNX#g6EXU-Jd>d1$(LB4b{h66gQ1* zI&c*`=?i!s>bgJeWs*W~^;Kg1zSV}+tNG2vY{w}}Yl*eiw)=@bL#*90G;MWh?8K#- z*_QMdGcNMB@2KN0?^oF~{`yoChXCRR;+e>9+@u#2HvNL-_icBF)#Eg0su`nSXal60 znQ3`!EDD0`qO12mDh(lgHPTt*r^4W%-pi&%(gq zu229B7eH7YI?S4zi1?u?GFHGN+UPOm!?C-FKub3uKZ)!t`+va`|= znU@N&+XG)lxOS{Rde@W^EJz#VTNY~^>6c~u8ot(bv9HX;zkyt7T1m3H{vCZ3^$fv3 z<=<_fz&}RN;qLR;LB_;m--njmPv^Y~In=7P!jLJYBhQq7QK{W3f@{{HLzC^vO>6Ip zSk59Wd__#9itV9lh1DtaWGlD>y8fsO@a7(z6hGt}bQ0t4w3|EyJ3slzT!xLjHfCEO-+l}Vrw_~6+Hi`SHYM{$BE(Wd4{FTEfMc`NMbfS z6R4u^1OC~dGV5vt14oF1mjuJihL%EmgNM8S@wtd2*2Z<&*J0-4n-Q8q=~z4Y6V#$4 z`jtG2QvOe6wh80~?zlv~8hS^#^(AFGGnV_WxTKfqP7#<}3lY+Tv{m`5aZlIdva)Ey zqq+dO3>V_BBPjDH!$!zJ^Jp%sAFI$-^~~j0mc#FX1xfZ;9YQl06qb=HmzSS)A<igl4qX_i@CzPyiZF1F{c48B9Tg$E}cG&I$8?P{&I3Df103<^xPXtNzK$=!OVtf4SV5o7!e7B)4q@#wyH*KLVQ?U1Rx#si8*dY%;5pNr+;W$g zk1~UXj`c(#1nDtTN}$>OJx_jzcXKBHZG8j&uOmPH5A$2I;h>|)%zvBT8cmg?`~ti5 z)ztnf^XmmCBE0QMR)0LI63v2J`&i-=^nq#W>bFrxyJz$_U#_P>x#boZA0fG1H zM4v5*h|OZm_zeDX297%nPdx||!yrgtq3s#<0*%VzfLTO8_Q#l}0(UdxfpKlY`uw_c zLX%F4{wDM!LJN#LndVA`r_7>z#r(EGJx)(6l$^xTCw5yvqWKCPkK@sB8I6EdRb?;T z;Wgo%9$PppE~6?9JS;7^eo>UizQ3_&)Ia(s$nCTCImvZ|{IHc4^)pV z=J-^S?EhK-*!{EVhEi@eddhol4>E^FRh-9L7M&q*HKTsA6O;+-3CM&`son|JN!Ip> zXYe>pnt8erS|B~q3maJ#W#0PW&ljJkpJb~G?PC9A{!GKoy%3^kAB$r@A9_3=fs+`6 zMFDh5TScj5iJkc6H{MDTt45tr^;5bU!u|Oz{QN_NT2}I^Zre+rRMF*Wyw>wcDVeOj zq&C}rnE*ax!tN)=sDrIId|2 zk1nyotY>0|A5phDsD3c@318_^}BT!!rJfIuTj8!fyB5z2D>; zNE~Iw=1Kss;WLS7kyOOu?2r38~$U_ix5DXAZ5G)XE5F8L( z5Ihik5CRZF5F!v_5E2kl5Hb*Q5DE}V5GoLA5E>9#5IT@YAdf-lK^Q=ufG~nEfiQzS z1z`bU1z`hW2jKwW1mObV2H^qW1>pnX2N3`f1Q7xe1`z=f1rY;z1|kk30U`+^1tJY1 z10o9|2OI{xEuP|k0YOB(a>0Ixl0t(|FVOz%awhiiO(QkuL%$@%u-*q%35XJb zbuSSp5s{D@k>b|dpUtA@i+lgN7vb^F*)PPe|1s6UlP|MwD8yC{&jS697w_F$s-k=+ zEaq-+SKG$~y@sGmJG|0$5?2=&7nkCIEy_aaXe3pkJi2ylT>RqVauU3@JaTLnZsOu< zTu!cvR?wIH&fG8)MJOqZodt>}E+Mb^cU=hyRXclaHZ)Z5b9aHQG_#hjg#a7avW=yJ zvfA$k!H(G2z=pw(x{Nt^9_GaYm4~>(I$5Bs5G~jbb|_yhGb_{`f^KSN>*;FwzdA5h zSO_~58(ru3c)>3TSvFV>J2+7HT5zCx5Ckb+*rF1Y04B)^{1mJAjlsGGrl z+@0ctJ>&rsHJCIHR1|^D3>GH}C5L76Kq(+xu-3a%0x(fwC=uw!h0-GEsKU5;!7?b! zffp(Yk%5))LIojiu+6(dbr>xln7n}Lg9(DNGz`WE*5QSX-<3MUu=&AKIeC~OKa?Lq zS^^f#4|ZrP4iggwJ6z(2Qox3|!I?%Z0Hubwz*K~w#4uF>C=Emf<}C2LlTrb&In%o{ zBV|PD30!$EI{JvYXuni$75yblLmWe|6?|!@hf}{A|RkW~l@J@gO0&f{D zZ0zpX0k$g)6@#$g! ze+G7>23rElzz0Gm4xVCr4$~9|YkI)mf?0?pY*74nD>PEz9iox|?~oEqN&-CN4)c`& zhi?gMxy#AJ&hHXy7^fsy-4bRm`Ma<{5^TyEwhrbHn9X2dBX>j5yGvfc-b#T_QAz_g zc9(q)!;%IQ6_~s<^eL&7lAQ9N`6;2HXv6;ZR23JOhl%k*358W0*tq{GRQ+?PDd{M1 zcl7(Y{Vq~?ewRr8KK|=ViU+nN4JAWh7l++~DWW*DCG1cUO7sBi=#6+SzYJ6o^1IMi z7HR@M<^P41E?f>Og78Kh)*}br5Y<0Roq#+v8W}PKqcIl210eVA-GhXZb5!1Hy}*hO zX?C>Jlx76W5J0E}Ss2ErfP422dWYlg(tC?D5AH4)`tm1#K(Y9{`~g_@`}5a%_P_Ir z$>wnIx^RYHZ|~B->-~Kl`#t(UHUEDbygLnL8iE0;(6IYKW@A-%qXr1>2668m)_aBD I>0e*}9~pOMWB>pF diff --git a/package/osx/package b/package/osx/package index e481353ff..8a4860b5d 100755 --- a/package/osx/package +++ b/package/osx/package @@ -30,8 +30,10 @@ cp "${ROOT_DIR}/HISTORY.txt" "/Volumes/${VOL_NAME}" hdiutil detach ${device} -echo "Resizing dmg" -hdiutil resize -size 250m ${TEMP_FILE} +min=`hdiutil resize ${TEMP_FILE} | awk \{print\ \$\1\}` +echo "Resizing dmg to ${min}" + +hdiutil resize -sectors ${min} ${TEMP_FILE} hdiutil convert "${TEMP_FILE}" -format UDZO -o "${OUT_FILE}" # cleanup From 162b0d7f758a5f1f0a024ba740cac68937bc9f7a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 10 Dec 2011 14:11:58 -0600 Subject: [PATCH 24/24] Because the UAVO field sorting required for revo changes all the object IDs, trigger a flash wipe on all existing boards with this upgrade. --- HISTORY.txt | 4 ++++ flight/PiOS/Common/pios_flashfs_objlist.c | 4 ++-- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/HISTORY.txt b/HISTORY.txt index 626a41593..aba9effab 100644 --- a/HISTORY.txt +++ b/HISTORY.txt @@ -1,5 +1,9 @@ Short summary of changes. For a complete list see the git log. +2011-12-10 +Merged a change that sorts the UAVO fields based on size. Because this changes +all of the objects, erase all existing flash files based on this. + 2011-11-04 New Spektrum/JR satellite receiver driver implementation. It now provides explicit selection of DSM2 (and DSMJ), DSMX (10bit) and diff --git a/flight/PiOS/Common/pios_flashfs_objlist.c b/flight/PiOS/Common/pios_flashfs_objlist.c index b252ef81e..e02683657 100644 --- a/flight/PiOS/Common/pios_flashfs_objlist.c +++ b/flight/PiOS/Common/pios_flashfs_objlist.c @@ -56,8 +56,8 @@ struct fileHeader { } __attribute__((packed)); -#define OBJECT_TABLE_MAGIC 0x85FB3C35 -#define OBJ_MAGIC 0x3015AE71 +#define OBJECT_TABLE_MAGIC 0x85FB3D35 +#define OBJ_MAGIC 0x3015A371 #define OBJECT_TABLE_START 0x00000010 #define OBJECT_TABLE_END 0x00001000 #define SECTOR_SIZE 0x00001000